From 241363934e3b6643b329f049879c6c063a026fad Mon Sep 17 00:00:00 2001 From: tbago Date: Fri, 16 Jun 2023 22:25:15 +0800 Subject: [PATCH 01/25] camera server : add start stop video subscribe, add start stop video example --- examples/camera_server/camera_client.cpp | 9 +- examples/camera_server/camera_server.cpp | 6 + .../plugins/camera_server/camera_server.cpp | 21 + .../camera_server/camera_server_impl.cpp | 43 +- .../camera_server/camera_server_impl.h | 11 +- .../plugins/camera_server/camera_server.h | 42 ++ .../camera_server/camera_server.grpc.pb.cc | 70 ++ .../camera_server/camera_server.grpc.pb.h | 326 ++++++++- .../camera_server/camera_server.pb.cc | 682 ++++++++++++++++-- .../camera_server/camera_server.pb.h | 648 ++++++++++++++++- .../camera_server_service_impl.h | 82 +++ 11 files changed, 1854 insertions(+), 86 deletions(-) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index e2190b22ca..3ba1f6f15a 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -47,8 +47,13 @@ int main(int argc, const char* argv[]) std::cout << info << std::endl; }); - auto take_photo_result = camera.take_photo(); - std::cout << "Take phto return : " << take_photo_result << std::endl; + auto operation_result = camera.take_photo(); + std::cout << "Take photo result : " << operation_result << std::endl; + operation_result = camera.start_video(); + std::cout << "Start video result : " << operation_result << std::endl; + + operation_result = camera.stop_video(); + std::cout << "Stop video result : " << operation_result << std::endl; return 0; } diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 64f94c8774..58963909e6 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -51,6 +51,12 @@ int main(int argc, char** argv) }); }); + camera_server.subscribe_start_video( + [](int32_t stream_id) { std::cout << "Start video record" << std::endl; }); + + camera_server.subscribe_stop_video( + [](int32_t stream_id) { std::cout << "Stop video record" << std::endl; }); + // Then set the initial state of everything. // TODO: this state is not guaranteed, e.g. a new system appears diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 832d23954b..857fe6b9e2 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -48,6 +48,27 @@ CameraServer::Result CameraServer::respond_take_photo( return _impl->respond_take_photo(take_photo_feedback, capture_info); } +CameraServer::StartVideoHandle +CameraServer::subscribe_start_video(const StartVideoCallback& callback) +{ + return _impl->subscribe_start_video(callback); +} + +void CameraServer::unsubscribe_start_video(StartVideoHandle handle) +{ + _impl->unsubscribe_start_video(handle); +} + +CameraServer::StopVideoHandle CameraServer::subscribe_stop_video(const StopVideoCallback& callback) +{ + return _impl->subscribe_stop_video(callback); +} + +void CameraServer::unsubscribe_stop_video(StopVideoHandle handle) +{ + _impl->unsubscribe_stop_video(handle); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 6ca64d15d9..03a447ed7e 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -291,6 +291,28 @@ CameraServer::Result CameraServerImpl::respond_take_photo( return CameraServer::Result::Success; } +CameraServer::StartVideoHandle +CameraServerImpl::subscribe_start_video(const CameraServer::StartVideoCallback& callback) +{ + return _start_video_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle handle) +{ + _start_video_callbacks.unsubscribe(handle); +} + +CameraServer::StopVideoHandle +CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback) +{ + return _stop_video_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle handle) +{ + return _stop_video_callbacks.unsubscribe(handle); +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -734,13 +756,18 @@ CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::Comm auto stream_id = static_cast(command.params.param1); auto status_frequency = command.params.param2; - UNUSED(stream_id); UNUSED(status_frequency); - LogDebug() << "unsupported video start capture request"; + if (_start_video_callbacks.empty()) { + LogDebug() << "video start capture requested with no video start capture subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } + + _start_video_callbacks(stream_id); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional @@ -748,12 +775,16 @@ CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::Comma { auto stream_id = static_cast(command.params.param1); - UNUSED(stream_id); + if (_stop_video_callbacks.empty()) { + LogDebug() << "video stop capture requested with no video stop capture subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported video stop capture request"; + _stop_video_callbacks(stream_id); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 6da2ce4483..268418aa8e 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -20,11 +20,18 @@ class CameraServerImpl : public ServerPluginImplBase { CameraServer::TakePhotoHandle subscribe_take_photo(const CameraServer::TakePhotoCallback& callback); void unsubscribe_take_photo(CameraServer::TakePhotoHandle handle); - CameraServer::Result respond_take_photo( CameraServer::TakePhotoFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info); + CameraServer::StartVideoHandle + subscribe_start_video(const CameraServer::StartVideoCallback& callback); + void unsubscribe_start_video(CameraServer::StartVideoHandle handle); + + CameraServer::StopVideoHandle + subscribe_stop_video(const CameraServer::StopVideoCallback& callback); + void unsubscribe_stop_video(CameraServer::StopVideoHandle handle); + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -49,6 +56,8 @@ class CameraServerImpl : public ServerPluginImplBase { int32_t _image_capture_count{}; CallbackList _take_photo_callbacks{}; + CallbackList _start_video_callbacks{}; + CallbackList _stop_video_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index e8ee0a8d34..0c64edc37e 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -262,6 +262,48 @@ class CameraServer : public ServerPluginBase { Result respond_take_photo(TakePhotoFeedback take_photo_feedback, CaptureInfo capture_info) const; + /** + * @brief Callback type for subscribe_start_video. + */ + using StartVideoCallback = std::function; + + /** + * @brief Handle type for subscribe_start_video. + */ + using StartVideoHandle = Handle; + + /** + * @brief Subscribe to start video requests. Each request received should response to using + * StartVideoResponse + */ + StartVideoHandle subscribe_start_video(const StartVideoCallback& callback); + + /** + * @brief Unsubscribe from subscribe_start_video + */ + void unsubscribe_start_video(StartVideoHandle handle); + + /** + * @brief Callback type for subscribe_stop_video. + */ + using StopVideoCallback = std::function; + + /** + * @brief Handle type for subscribe_stop_video. + */ + using StopVideoHandle = Handle; + + /** + * @brief Subscribe to stop video requests. Each request received should response to using + * StopVideoResponse + */ + StopVideoHandle subscribe_stop_video(const StopVideoCallback& callback); + + /** + * @brief Unsubscribe from subscribe_stop_video + */ + void unsubscribe_stop_video(StopVideoHandle handle); + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index 815dbfdb83..d77a8f3eb1 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -28,6 +28,8 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -41,6 +43,8 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_SetInProgress_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -128,6 +132,38 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhot return result; } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), rpcmethod_SubscribeStartVideo_, context, request); +} + +void CameraServerService::Stub::async::SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStartVideo_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideo_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideo_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), rpcmethod_SubscribeStopVideo_, context, request); +} + +void CameraServerService::Stub::async::SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStopVideo_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, false, nullptr); +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -169,6 +205,26 @@ CameraServerService::Service::Service() { ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* resp) { return service->RespondTakePhoto(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[4], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StartVideoResponse>* writer) { + return service->SubscribeStartVideo(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[5], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { + return service->SubscribeStopVideo(ctx, req, writer); + }, this))); } CameraServerService::Service::~Service() { @@ -202,6 +258,20 @@ ::grpc::Status CameraServerService::Service::RespondTakePhoto(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index f5bc2b5682..925d9fa82d 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -72,6 +72,26 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } + // Subscribe to start video requests. Each request received should response to using StartVideoResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> AsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(AsyncSubscribeStartVideoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); + } + // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> AsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(AsyncSubscribeStopVideoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -86,6 +106,10 @@ class CameraServerService final { // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to start video requests. Each request received should response to using StartVideoResponse + virtual void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) = 0; + // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + virtual void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -100,6 +124,12 @@ class CameraServerService final { virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -134,6 +164,24 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> AsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(AsyncSubscribeStartVideoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> AsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(AsyncSubscribeStopVideoRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -144,6 +192,8 @@ class CameraServerService final { void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) override; void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) override; + void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -164,10 +214,18 @@ class CameraServerService final { ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* PrepareAsyncSubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* AsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* PrepareAsyncRespondTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideo_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideo_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -183,6 +241,10 @@ class CameraServerService final { virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); + // Subscribe to start video requests. Each request received should response to using StartVideoResponse + virtual ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer); + // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + virtual ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -264,7 +326,47 @@ class CameraServerService final { ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > AsyncService; + template + class WithAsyncMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodAsync(4); + } + ~WithAsyncMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(4, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodAsync(5); + } + ~WithAsyncMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -368,7 +470,51 @@ class CameraServerService final { virtual ::grpc::ServerUnaryReactor* RespondTakePhoto( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > CallbackService; + template + class WithCallbackMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodCallback(4, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request) { return this->SubscribeStartVideo(context, request); })); + } + ~WithCallbackMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodCallback(5, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request) { return this->SubscribeStopVideo(context, request); })); + } + ~WithCallbackMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -439,6 +585,40 @@ class CameraServerService final { } }; template + class WithGenericMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodGeneric(4); + } + ~WithGenericMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodGeneric(5); + } + ~WithGenericMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -519,6 +699,46 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodRaw(4); + } + ~WithRawMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStartVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(4, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodRaw(5); + } + ~WithRawMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -607,6 +827,50 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodRawCallback(4, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideo(context, request); })); + } + ~WithRawCallbackMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStartVideo( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodRawCallback(5, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideo(context, request); })); + } + ~WithRawCallbackMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStopVideo( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -715,8 +979,62 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeTakePhoto(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest,::mavsdk::rpc::camera_server::TakePhotoResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeStartVideo() { + ::grpc::Service::MarkMethodStreamed(4, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>* streamer) { + return this->StreamedSubscribeStartVideo(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeStartVideo(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest,::mavsdk::rpc::camera_server::StartVideoResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeStopVideo() { + ::grpc::Service::MarkMethodStreamed(5, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>* streamer) { + return this->StreamedSubscribeStopVideo(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest,::mavsdk::rpc::camera_server::StopVideoResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index a019c2673b..c544e417c9 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -115,6 +115,64 @@ struct TakePhotoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeStartVideoRequest::SubscribeStartVideoRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeStartVideoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeStartVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeStartVideoRequestDefaultTypeInternal() {} + union { + SubscribeStartVideoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; +template +PROTOBUF_CONSTEXPR StartVideoResponse::StartVideoResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StartVideoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StartVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StartVideoResponseDefaultTypeInternal() {} + union { + StartVideoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeStopVideoRequest::SubscribeStopVideoRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeStopVideoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeStopVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeStopVideoRequestDefaultTypeInternal() {} + union { + SubscribeStopVideoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_default_instance_; +template +PROTOBUF_CONSTEXPR StopVideoResponse::StopVideoResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StopVideoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StopVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StopVideoResponseDefaultTypeInternal() {} + union { + StopVideoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; +template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -286,7 +344,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -348,6 +406,40 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, _impl_.index_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, _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::camera_server::StartVideoResponse, _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::camera_server::StartVideoResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, _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::camera_server::StopVideoResponse, _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::camera_server::StopVideoResponse, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -453,13 +545,17 @@ static const ::_pbi::MigrationSchema { 29, 38, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, { 39, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, { 47, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - { 56, 66, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 68, 77, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 78, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 97, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 109, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 121, 135, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 141, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 56, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, + { 64, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, + { 73, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, + { 81, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, + { 90, 100, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 102, 111, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 112, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 131, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 143, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 155, 169, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 175, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -469,6 +565,10 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_TakePhotoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeStartVideoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StartVideoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeStopVideoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StopVideoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -490,55 +590,65 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "sult\030\001 \001(\0132,.mavsdk.rpc.camera_server.Ca" "meraServerResult\"\033\n\031SubscribeTakePhotoRe" "quest\"\"\n\021TakePhotoResponse\022\r\n\005index\030\001 \001(" - "\005\"\240\001\n\027RespondTakePhotoRequest\022H\n\023take_ph" - "oto_feedback\030\001 \001(\0162+.mavsdk.rpc.camera_s" - "erver.TakePhotoFeedback\022;\n\014capture_info\030" - "\002 \001(\0132%.mavsdk.rpc.camera_server.Capture" - "Info\"f\n\030RespondTakePhotoResponse\022J\n\024came" - "ra_server_result\030\001 \001(\0132,.mavsdk.rpc.came" - "ra_server.CameraServerResult\"\276\002\n\013Informa" - "tion\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030" - "\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal" - "_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_si" - "ze_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006" - " \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036" - "\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens_i" - "d\030\t \001(\r\022\037\n\027definition_file_version\030\n \001(\r" - "\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Positio" - "n\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg" - "\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023r" - "elative_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t" - "\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001" - "(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".m" - "avsdk.rpc.camera_server.Position\022A\n\023atti" - "tude_quaternion\030\002 \001(\0132$.mavsdk.rpc.camer" - "a_server.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004" - "\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010f" - "ile_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006" - "result\030\001 \001(\01623.mavsdk.rpc.camera_server." - "CameraServerResult.Result\022\022\n\nresult_str\030" - "\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" - "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" - "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" - "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" - "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" - "M\020\010*\216\001\n\021TakePhotoFeedback\022\037\n\033TAKE_PHOTO_" - "FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBAC" - "K_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032" - "TAKE_PHOTO_FEEDBACK_FAILED\020\0032\211\004\n\023CameraS" - "erverService\022y\n\016SetInformation\022/.mavsdk." - "rpc.camera_server.SetInformationRequest\032" - "0.mavsdk.rpc.camera_server.SetInformatio" - "nResponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsd" - "k.rpc.camera_server.SetInProgressRequest" - "\032/.mavsdk.rpc.camera_server.SetInProgres" - "sResponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223." - "mavsdk.rpc.camera_server.SubscribeTakePh" - "otoRequest\032+.mavsdk.rpc.camera_server.Ta" - "kePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePh" - "oto\0221.mavsdk.rpc.camera_server.RespondTa" - "kePhotoRequest\0322.mavsdk.rpc.camera_serve" - "r.RespondTakePhotoResponse\"\004\200\265\030\001B,\n\027io.m" + "\005\"\034\n\032SubscribeStartVideoRequest\"\'\n\022Start" + "VideoResponse\022\021\n\tstream_id\030\001 \001(\005\"\033\n\031Subs" + "cribeStopVideoRequest\"&\n\021StopVideoRespon" + "se\022\021\n\tstream_id\030\001 \001(\005\"\240\001\n\027RespondTakePho" + "toRequest\022H\n\023take_photo_feedback\030\001 \001(\0162+" + ".mavsdk.rpc.camera_server.TakePhotoFeedb" + "ack\022;\n\014capture_info\030\002 \001(\0132%.mavsdk.rpc.c" + "amera_server.CaptureInfo\"f\n\030RespondTakeP" + "hotoResponse\022J\n\024camera_server_result\030\001 \001" + "(\0132,.mavsdk.rpc.camera_server.CameraServ" + "erResult\"\276\002\n\013Information\022\023\n\013vendor_name\030" + "\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\030\n\020firmware_ve" + "rsion\030\003 \001(\t\022\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031" + "horizontal_sensor_size_mm\030\005 \001(\002\022\037\n\027verti" + "cal_sensor_size_mm\030\006 \001(\002\022 \n\030horizontal_r" + "esolution_px\030\007 \001(\r\022\036\n\026vertical_resolutio" + "n_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(\r\022\037\n\027definitio" + "n_file_version\030\n \001(\r\022\033\n\023definition_file_" + "uri\030\013 \001(\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 " + "\001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_a" + "ltitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004" + " \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002" + "\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224" + "\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_ser" + "ver.Position\022A\n\023attitude_quaternion\030\002 \001(" + "\0132$.mavsdk.rpc.camera_server.Quaternion\022" + "\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010" + "\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Ca" + "meraServerResult\022C\n\006result\030\001 \001(\01623.mavsd" + "k.rpc.camera_server.CameraServerResult.R" + "esult\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016" + "RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022" + "RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n" + "\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RE" + "SULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020" + "\007\022\024\n\020RESULT_NO_SYSTEM\020\010*\216\001\n\021TakePhotoFee" + "dback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032" + "\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO" + "_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_" + "FAILED\020\0032\215\006\n\023CameraServerService\022y\n\016SetI" + "nformation\022/.mavsdk.rpc.camera_server.Se" + "tInformationRequest\0320.mavsdk.rpc.camera_" + "server.SetInformationResponse\"\004\200\265\030\001\022v\n\rS" + "etInProgress\022..mavsdk.rpc.camera_server." + "SetInProgressRequest\032/.mavsdk.rpc.camera" + "_server.SetInProgressResponse\"\004\200\265\030\001\022~\n\022S" + "ubscribeTakePhoto\0223.mavsdk.rpc.camera_se" + "rver.SubscribeTakePhotoRequest\032+.mavsdk." + "rpc.camera_server.TakePhotoResponse\"\004\200\265\030" + "\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.rpc.cam" + "era_server.RespondTakePhotoRequest\0322.mav" + "sdk.rpc.camera_server.RespondTakePhotoRe" + "sponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVideo\0224.m" + "avsdk.rpc.camera_server.SubscribeStartVi" + "deoRequest\032,.mavsdk.rpc.camera_server.St" + "artVideoResponse\"\004\200\265\030\0000\001\022~\n\022SubscribeSto" + "pVideo\0223.mavsdk.rpc.camera_server.Subscr" + "ibeStopVideoRequest\032+.mavsdk.rpc.camera_" + "server.StopVideoResponse\"\004\200\265\030\0000\001B,\n\027io.m" "avsdk.camera_serverB\021CameraServerProtob\006" "proto3" }; @@ -550,13 +660,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 2486, + 2886, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 13, + 17, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -1640,6 +1750,430 @@ ::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { } // =================================================================== +class SubscribeStartVideoRequest::_Internal { + public: +}; + +SubscribeStartVideoRequest::SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) +} +SubscribeStartVideoRequest::SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStartVideoRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); +} +// =================================================================== + +class StartVideoResponse::_Internal { + public: +}; + +StartVideoResponse::StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoResponse) +} +StartVideoResponse::StartVideoResponse(const StartVideoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoResponse) +} + +inline void StartVideoResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StartVideoResponse::~StartVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StartVideoResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StartVideoResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StartVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StartVideoResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StartVideoResponse) + return target; +} + +::size_t StartVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StartVideoResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoResponse::GetClassData() const { return &_class_data_; } + + +void StartVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StartVideoResponse::CopyFrom(const StartVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StartVideoResponse::IsInitialized() const { + return true; +} + +void StartVideoResponse::InternalSwap(StartVideoResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StartVideoResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); +} +// =================================================================== + +class SubscribeStopVideoRequest::_Internal { + public: +}; + +SubscribeStopVideoRequest::SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) +} +SubscribeStopVideoRequest::SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStopVideoRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); +} +// =================================================================== + +class StopVideoResponse::_Internal { + public: +}; + +StopVideoResponse::StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoResponse) +} +StopVideoResponse::StopVideoResponse(const StopVideoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoResponse) +} + +inline void StopVideoResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StopVideoResponse::~StopVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StopVideoResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StopVideoResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StopVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StopVideoResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StopVideoResponse) + return target; +} + +::size_t StopVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StopVideoResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoResponse::GetClassData() const { return &_class_data_; } + + +void StopVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StopVideoResponse::CopyFrom(const StopVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StopVideoResponse::IsInitialized() const { + return true; +} + +void StopVideoResponse::InternalSwap(StopVideoResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); +} +// =================================================================== + class RespondTakePhotoRequest::_Internal { public: using HasBits = decltype(std::declval()._impl_._has_bits_); @@ -1878,7 +2412,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); } // =================================================================== @@ -2083,7 +2617,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); } // =================================================================== @@ -2668,7 +3202,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); } // =================================================================== @@ -2973,7 +3507,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); } // =================================================================== @@ -3278,7 +3812,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); } // =================================================================== @@ -3681,7 +4215,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); } // =================================================================== @@ -3910,7 +4444,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -3941,6 +4475,22 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::TakePhotoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::TakePhotoResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StartVideoResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StartVideoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StartVideoResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 4e6ce34cd4..cc3322ae0c 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -89,6 +89,18 @@ extern SetInformationRequestDefaultTypeInternal _SetInformationRequest_default_i class SetInformationResponse; struct SetInformationResponseDefaultTypeInternal; extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; +class StartVideoResponse; +struct StartVideoResponseDefaultTypeInternal; +extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; +class StopVideoResponse; +struct StopVideoResponseDefaultTypeInternal; +extern StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; +class SubscribeStartVideoRequest; +struct SubscribeStartVideoRequestDefaultTypeInternal; +extern SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; +class SubscribeStopVideoRequest; +struct SubscribeStopVideoRequestDefaultTypeInternal; +extern SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_default_instance_; class SubscribeTakePhotoRequest; struct SubscribeTakePhotoRequestDefaultTypeInternal; extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; @@ -122,6 +134,14 @@ ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage<: template <> ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStopVideoRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); @@ -1123,6 +1143,564 @@ class TakePhotoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- +class SubscribeStartVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { + public: + inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from); + SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept + : SubscribeStartVideoRequest() { + *this = ::std::move(from); + } + + inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeStartVideoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeStartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeStartVideoRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeStartVideoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeStartVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStartVideoRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStartVideoRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeStartVideoRequest"; + } + protected: + explicit SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class StartVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { + public: + inline StartVideoResponse() : StartVideoResponse(nullptr) {} + ~StartVideoResponse() override; + template + explicit PROTOBUF_CONSTEXPR StartVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + StartVideoResponse(const StartVideoResponse& from); + StartVideoResponse(StartVideoResponse&& from) noexcept + : StartVideoResponse() { + *this = ::std::move(from); + } + + inline StartVideoResponse& operator=(const StartVideoResponse& from) { + CopyFrom(from); + return *this; + } + inline StartVideoResponse& operator=(StartVideoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 StartVideoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StartVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + friend void swap(StartVideoResponse& a, StartVideoResponse& b) { + a.Swap(&b); + } + inline void Swap(StartVideoResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(StartVideoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StartVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StartVideoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StartVideoResponse& from) { + StartVideoResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StartVideoResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.StartVideoResponse"; + } + protected: + explicit StartVideoResponse(::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 { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeStopVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { + public: + inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from); + SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept + : SubscribeStopVideoRequest() { + *this = ::std::move(from); + } + + inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeStopVideoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeStopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeStopVideoRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeStopVideoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeStopVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStopVideoRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStopVideoRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeStopVideoRequest"; + } + protected: + explicit SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class StopVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { + public: + inline StopVideoResponse() : StopVideoResponse(nullptr) {} + ~StopVideoResponse() override; + template + explicit PROTOBUF_CONSTEXPR StopVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + StopVideoResponse(const StopVideoResponse& from); + StopVideoResponse(StopVideoResponse&& from) noexcept + : StopVideoResponse() { + *this = ::std::move(from); + } + + inline StopVideoResponse& operator=(const StopVideoResponse& from) { + CopyFrom(from); + return *this; + } + inline StopVideoResponse& operator=(StopVideoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 StopVideoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StopVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(StopVideoResponse& a, StopVideoResponse& b) { + a.Swap(&b); + } + inline void Swap(StopVideoResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(StopVideoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StopVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StopVideoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StopVideoResponse& from) { + StopVideoResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StopVideoResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.StopVideoResponse"; + } + protected: + explicit StopVideoResponse(::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 { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RespondTakePhotoRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: @@ -1179,7 +1757,7 @@ class RespondTakePhotoRequest final : &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 10; friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); @@ -1351,7 +1929,7 @@ class RespondTakePhotoResponse final : &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 11; friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); @@ -1511,7 +2089,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 12; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -1826,7 +2404,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 13; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -2017,7 +2595,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 14; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -2208,7 +2786,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 15; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -2442,7 +3020,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 16; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -2929,6 +3507,62 @@ inline void TakePhotoResponse::_internal_set_index(::int32_t value) { // ------------------------------------------------------------------- +// SubscribeStartVideoRequest + +// ------------------------------------------------------------------- + +// StartVideoResponse + +// int32 stream_id = 1; +inline void StartVideoResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StartVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) + return _internal_stream_id(); +} +inline void StartVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) +} +inline ::int32_t StartVideoResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeStopVideoRequest + +// ------------------------------------------------------------------- + +// StopVideoResponse + +// int32 stream_id = 1; +inline void StopVideoResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StopVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) + return _internal_stream_id(); +} +inline void StopVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) +} +inline ::int32_t StopVideoResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + // RespondTakePhotoRequest // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 39ddeb1f55..84e1cf9144 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -437,6 +437,88 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeStartVideo( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::StartVideoHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_start_video( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t start_video) { + rpc::camera_server::StartVideoResponse rpc_response; + + rpc_response.set_stream_id(start_video); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_start_video(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeStopVideo( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::StopVideoHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_stop_video( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t stop_video) { + rpc::camera_server::StopVideoResponse rpc_response; + + rpc_response.set_stream_id(stop_video); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_stop_video(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); From 5014dfccf8dee75ae64cbc8c22536bc2b48a3b56 Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 17 Jun 2023 16:03:23 +0800 Subject: [PATCH 02/25] camera server : add start stop video streaming, add stream id in camera side --- examples/camera_server/camera_client.cpp | 17 +- examples/camera_server/camera_server.cpp | 76 +- src/mavsdk/plugins/camera/camera.cpp | 8 +- src/mavsdk/plugins/camera/camera_impl.cpp | 14 +- src/mavsdk/plugins/camera/camera_impl.h | 8 +- .../camera/include/plugins/camera/camera.h | 4 +- src/mavsdk/plugins/camera/mocks/camera_mock.h | 4 +- .../plugins/camera_server/camera_server.cpp | 22 + .../camera_server/camera_server_impl.cpp | 44 +- .../camera_server/camera_server_impl.h | 10 + .../plugins/camera_server/camera_server.h | 44 ++ .../src/generated/camera/camera.pb.cc | 741 ++++++++++++------ .../src/generated/camera/camera.pb.h | 134 +++- .../camera_server/camera_server.grpc.pb.cc | 70 ++ .../camera_server/camera_server.grpc.pb.h | 326 +++++++- .../camera_server/camera_server.pb.cc | 702 +++++++++++++++-- .../camera_server/camera_server.pb.h | 648 ++++++++++++++- .../src/plugins/camera/camera_service_impl.h | 18 +- .../camera_server_service_impl.h | 82 ++ .../test/camera_service_impl_test.cpp | 8 +- 20 files changed, 2582 insertions(+), 398 deletions(-) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 3ba1f6f15a..e3e6588a0c 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -5,6 +5,8 @@ #include #include +static void do_camera_operation(mavsdk::Camera& camera); + int main(int argc, const char* argv[]) { // we run client plugins to act as the GCS @@ -47,6 +49,13 @@ int main(int argc, const char* argv[]) std::cout << info << std::endl; }); + do_camera_operation(camera); + + return 0; +} + +void do_camera_operation(mavsdk::Camera& camera) +{ auto operation_result = camera.take_photo(); std::cout << "Take photo result : " << operation_result << std::endl; @@ -55,5 +64,11 @@ int main(int argc, const char* argv[]) operation_result = camera.stop_video(); std::cout << "Stop video result : " << operation_result << std::endl; - return 0; + + // the camera can have multi video stream so may need the stream id + operation_result = camera.start_video_streaming(2); + std::cout << "start video streaming result : " << operation_result << std::endl; + + operation_result = camera.stop_video_streaming(2); + std::cout << "stop video streaming result : " << operation_result << std::endl; } diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 58963909e6..aec550bccb 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -3,6 +3,8 @@ #include #include +static void subscribe_camera_operation(mavsdk::CameraServer& camera_server); + int main(int argc, char** argv) { mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::Mavsdk::ComponentType::Camera}}; @@ -18,7 +20,43 @@ int main(int argc, char** argv) auto camera_server = mavsdk::CameraServer{mavsdk.server_component()}; // First add all subscriptions. This defines the camera capabilities. + subscribe_camera_operation(camera_server); + + // TODO: this state is not guaranteed, e.g. a new system appears + // while a capture is in progress + camera_server.set_in_progress(false); + + // Finally call set_information() to "activate" the camera plugin. + + auto ret = camera_server.set_information({ + .vendor_name = "MAVSDK", + .model_name = "Example Camera Server", + .firmware_version = "1.0.0", + .focal_length_mm = 3.0, + .horizontal_sensor_size_mm = 3.68, + .vertical_sensor_size_mm = 2.76, + .horizontal_resolution_px = 3280, + .vertical_resolution_px = 2464, + .lens_id = 0, + .definition_file_version = 0, // TODO: add this + .definition_file_uri = "", // TODO: implement this using MAVLink FTP + }); + + if (ret != mavsdk::CameraServer::Result::Success) { + std::cerr << "Failed to set camera info, exiting" << std::endl; + return 2; + } + + // works as a server and never quit + while (true) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } + + return 0; +} +static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) +{ camera_server.subscribe_take_photo([&camera_server](int32_t index) { camera_server.set_in_progress(true); @@ -57,37 +95,9 @@ int main(int argc, char** argv) camera_server.subscribe_stop_video( [](int32_t stream_id) { std::cout << "Stop video record" << std::endl; }); - // Then set the initial state of everything. - - // TODO: this state is not guaranteed, e.g. a new system appears - // while a capture is in progress - camera_server.set_in_progress(false); + camera_server.subscribe_start_video_streaming( + [](int32_t stream_id) { std::cout << "Start video streaming " << stream_id << std::endl; }); - // Finally call set_information() to "activate" the camera plugin. - - auto ret = camera_server.set_information({ - .vendor_name = "MAVSDK", - .model_name = "Example Camera Server", - .firmware_version = "1.0.0", - .focal_length_mm = 3.0, - .horizontal_sensor_size_mm = 3.68, - .vertical_sensor_size_mm = 2.76, - .horizontal_resolution_px = 3280, - .vertical_resolution_px = 2464, - .lens_id = 0, - .definition_file_version = 0, // TODO: add this - .definition_file_uri = "", // TODO: implement this using MAVLink FTP - }); - - if (ret != mavsdk::CameraServer::Result::Success) { - std::cerr << "Failed to set camera info, exiting" << std::endl; - return 2; - } - - // works as a server and never quit - while (true) { - std::this_thread::sleep_for(std::chrono::seconds(1)); - } - - return 0; -} + camera_server.subscribe_stop_video_streaming( + [](int32_t stream_id) { std::cout << "Stop video streaming " << stream_id << std::endl; }); +} \ No newline at end of file diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index 737cd90711..21abdc9cec 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -90,14 +90,14 @@ Camera::Result Camera::stop_video() const return _impl->stop_video(); } -Camera::Result Camera::start_video_streaming() const +Camera::Result Camera::start_video_streaming(int32_t stream_id) const { - return _impl->start_video_streaming(); + return _impl->start_video_streaming(stream_id); } -Camera::Result Camera::stop_video_streaming() const +Camera::Result Camera::stop_video_streaming(int32_t stream_id) const { - return _impl->stop_video_streaming(); + return _impl->stop_video_streaming(stream_id); } void Camera::set_mode_async(Mode mode, const ResultCallback callback) diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 1201ff1fec..d3ce513875 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -413,21 +413,23 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_request_storage_info( return cmd_req_storage_info; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming() +MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming(int32_t stream_id) { MavlinkCommandSender::CommandLong cmd_start_video_streaming{}; cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING; + cmd_start_video_streaming.params.maybe_param1 = stream_id; cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; return cmd_start_video_streaming; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming() +MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming(int32_t stream_id) { MavlinkCommandSender::CommandLong cmd_stop_video_streaming{}; cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING; + cmd_stop_video_streaming.params.maybe_param1 = stream_id; cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; return cmd_stop_video_streaming; @@ -605,7 +607,7 @@ void CameraImpl::unsubscribe_information(Camera::InformationHandle handle) _information.subscription_callbacks.unsubscribe(handle); } -Camera::Result CameraImpl::start_video_streaming() +Camera::Result CameraImpl::start_video_streaming(int32_t stream_id) { std::lock_guard lock(_video_stream_info.mutex); @@ -615,7 +617,7 @@ Camera::Result CameraImpl::start_video_streaming() } // TODO Check whether we're in video mode - auto command = make_command_start_video_streaming(); + auto command = make_command_start_video_streaming(stream_id); auto result = camera_result_from_command_result(_system_impl->send_command(command)); // if (result == Camera::Result::Success) { @@ -626,12 +628,12 @@ Camera::Result CameraImpl::start_video_streaming() return result; } -Camera::Result CameraImpl::stop_video_streaming() +Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id) { // TODO I think we need to maintain current state, whether we issued // video capture request or video streaming request, etc.We shouldn't // send stop video streaming if we've not started it! - auto command = make_command_stop_video_streaming(); + auto command = make_command_stop_video_streaming(stream_id); auto result = camera_result_from_command_result(_system_impl->send_command(command)); { diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index c8dde65dee..f9f3f7d4f1 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -52,8 +52,8 @@ class CameraImpl : public PluginImplBase { subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback); void unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle); - Camera::Result start_video_streaming(); - Camera::Result stop_video_streaming(); + Camera::Result start_video_streaming(int32_t stream_id); + Camera::Result stop_video_streaming(int32_t stream_id); Camera::Result set_mode(const Camera::Mode mode); void set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback); @@ -196,8 +196,8 @@ class CameraImpl : public PluginImplBase { MavlinkCommandSender::CommandLong make_command_start_video(float capture_status_rate_hz); MavlinkCommandSender::CommandLong make_command_stop_video(); - MavlinkCommandSender::CommandLong make_command_start_video_streaming(); - MavlinkCommandSender::CommandLong make_command_stop_video_streaming(); + MavlinkCommandSender::CommandLong make_command_start_video_streaming(int32_t stream_id); + MavlinkCommandSender::CommandLong make_command_stop_video_streaming(int32_t stream_id); MavlinkCommandSender::CommandLong make_command_request_video_stream_info(); MavlinkCommandSender::CommandLong make_command_request_video_stream_status(); diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index a88d6ff45d..d9f4c93a6c 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -599,7 +599,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result start_video_streaming() const; + Result start_video_streaming(int32_t stream_id) const; /** * @brief Stop current video streaming. @@ -608,7 +608,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result stop_video_streaming() const; + Result stop_video_streaming(int32_t stream_id) const; /** * @brief Set camera mode. diff --git a/src/mavsdk/plugins/camera/mocks/camera_mock.h b/src/mavsdk/plugins/camera/mocks/camera_mock.h index ec2f713bdf..9941057012 100644 --- a/src/mavsdk/plugins/camera/mocks/camera_mock.h +++ b/src/mavsdk/plugins/camera/mocks/camera_mock.h @@ -13,8 +13,8 @@ class MockCamera { MOCK_CONST_METHOD0(stop_photo_interval, Camera::Result()){}; MOCK_CONST_METHOD0(start_video, Camera::Result()){}; MOCK_CONST_METHOD0(stop_video, Camera::Result()){}; - MOCK_CONST_METHOD0(start_video_streaming, Camera::Result()){}; - MOCK_CONST_METHOD0(stop_video_streaming, Camera::Result()){}; + MOCK_CONST_METHOD1(start_video_streaming, Camera::Result(int32_t stream_id)){}; + MOCK_CONST_METHOD1(stop_video_streaming, Camera::Result(int32_t strema_id)){}; MOCK_CONST_METHOD1(set_mode, Camera::Result(Camera::Mode)){}; MOCK_CONST_METHOD1(set_setting, Camera::Result(Camera::Setting)){}; MOCK_CONST_METHOD1(get_setting, std::pair(Camera::Setting)){}; diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 857fe6b9e2..9c664d0713 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -69,6 +69,28 @@ void CameraServer::unsubscribe_stop_video(StopVideoHandle handle) _impl->unsubscribe_stop_video(handle); } +CameraServer::StartVideoStreamingHandle +CameraServer::subscribe_start_video_streaming(const StartVideoStreamingCallback& callback) +{ + return _impl->subscribe_start_video_streaming(callback); +} + +void CameraServer::unsubscribe_start_video_streaming(StartVideoStreamingHandle handle) +{ + _impl->unsubscribe_start_video_streaming(handle); +} + +CameraServer::StopVideoStreamingHandle +CameraServer::subscribe_stop_video_streaming(const StopVideoStreamingCallback& callback) +{ + return _impl->subscribe_stop_video_streaming(callback); +} + +void CameraServer::unsubscribe_stop_video_streaming(StopVideoStreamingHandle handle) +{ + _impl->unsubscribe_stop_video_streaming(handle); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 03a447ed7e..f624dd4926 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -313,6 +313,30 @@ void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle hand return _stop_video_callbacks.unsubscribe(handle); } +CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming( + const CameraServer::StartVideoStreamingCallback& callback) +{ + return _start_video_streaming_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_start_video_streaming( + CameraServer::StartVideoStreamingHandle handle) +{ + return _start_video_streaming_callbacks.unsubscribe(handle); +} + +CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming( + const CameraServer::StopVideoStreamingCallback& callback) +{ + return _stop_video_streaming_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_stop_video_streaming( + CameraServer::StopVideoStreamingHandle handle) +{ + return _stop_video_streaming_callbacks.unsubscribe(handle); +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -792,12 +816,16 @@ CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::Co { auto stream_id = static_cast(command.params.param1); - UNUSED(stream_id); + if (_start_video_streaming_callbacks.empty()) { + LogDebug() << "video start streaming requested with no video start streaming subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported video start streaming request"; + _start_video_streaming_callbacks(stream_id); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional @@ -805,12 +833,16 @@ CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::Com { auto stream_id = static_cast(command.params.param1); - UNUSED(stream_id); + if (_stop_video_streaming_callbacks.empty()) { + LogDebug() << "video stop streaming requested with no video stop streaming subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported video stop streaming request"; + _stop_video_streaming_callbacks(stream_id); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional CameraServerImpl::process_video_stream_information_request( diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 268418aa8e..a9ea724c76 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -32,6 +32,14 @@ class CameraServerImpl : public ServerPluginImplBase { subscribe_stop_video(const CameraServer::StopVideoCallback& callback); void unsubscribe_stop_video(CameraServer::StopVideoHandle handle); + CameraServer::StartVideoStreamingHandle + subscribe_start_video_streaming(const CameraServer::StartVideoStreamingCallback& callback); + void unsubscribe_start_video_streaming(CameraServer::StartVideoStreamingHandle handle); + + CameraServer::StopVideoStreamingHandle + subscribe_stop_video_streaming(const CameraServer::StopVideoStreamingCallback& callback); + void unsubscribe_stop_video_streaming(CameraServer::StopVideoStreamingHandle handle); + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -58,6 +66,8 @@ class CameraServerImpl : public ServerPluginImplBase { CallbackList _take_photo_callbacks{}; CallbackList _start_video_callbacks{}; CallbackList _stop_video_callbacks{}; + CallbackList _start_video_streaming_callbacks{}; + CallbackList _stop_video_streaming_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 0c64edc37e..d9a3adc8b7 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -304,6 +304,50 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_stop_video(StopVideoHandle handle); + /** + * @brief Callback type for subscribe_start_video_streaming. + */ + using StartVideoStreamingCallback = std::function; + + /** + * @brief Handle type for subscribe_start_video_streaming. + */ + using StartVideoStreamingHandle = Handle; + + /** + * @brief Subscribe to start video streaming requests. Each request received should response to + * using StartVideoStreamingResponse + */ + StartVideoStreamingHandle + subscribe_start_video_streaming(const StartVideoStreamingCallback& callback); + + /** + * @brief Unsubscribe from subscribe_start_video_streaming + */ + void unsubscribe_start_video_streaming(StartVideoStreamingHandle handle); + + /** + * @brief Callback type for subscribe_stop_video_streaming. + */ + using StopVideoStreamingCallback = std::function; + + /** + * @brief Handle type for subscribe_stop_video_streaming. + */ + using StopVideoStreamingHandle = Handle; + + /** + * @brief Subscribe to stop video streaming requests. Each request received should response to + * using StopVideoStreamingResponse + */ + StopVideoStreamingHandle + subscribe_stop_video_streaming(const StopVideoStreamingCallback& callback); + + /** + * @brief Unsubscribe from subscribe_stop_video_streaming + */ + void unsubscribe_stop_video_streaming(StopVideoStreamingHandle handle); + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index e593ae70c8..81e95c2d2e 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -200,7 +200,10 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; template PROTOBUF_CONSTEXPR StartVideoStreamingRequest::StartVideoStreamingRequest( - ::_pbi::ConstantInitialized) {} + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} struct StartVideoStreamingRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR StartVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~StartVideoStreamingRequestDefaultTypeInternal() {} @@ -229,7 +232,10 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoStreamingResponseDefaultTypeInternal _StartVideoStreamingResponse_default_instance_; template PROTOBUF_CONSTEXPR StopVideoStreamingRequest::StopVideoStreamingRequest( - ::_pbi::ConstantInitialized) {} + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} struct StopVideoStreamingRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR StopVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~StopVideoStreamingRequestDefaultTypeInternal() {} @@ -1077,6 +1083,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingRequest, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1095,6 +1102,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingRequest, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1531,47 +1539,47 @@ static const ::_pbi::MigrationSchema { 91, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoRequest)}, { 99, 108, -1, sizeof(::mavsdk::rpc::camera::StopVideoResponse)}, { 109, -1, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingRequest)}, - { 117, 126, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingResponse)}, - { 127, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingRequest)}, - { 135, 144, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingResponse)}, - { 145, -1, -1, sizeof(::mavsdk::rpc::camera::SetModeRequest)}, - { 154, 163, -1, sizeof(::mavsdk::rpc::camera::SetModeResponse)}, - { 164, -1, -1, sizeof(::mavsdk::rpc::camera::ListPhotosRequest)}, - { 173, 183, -1, sizeof(::mavsdk::rpc::camera::ListPhotosResponse)}, - { 185, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeInformationRequest)}, - { 193, 202, -1, sizeof(::mavsdk::rpc::camera::InformationResponse)}, - { 203, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeModeRequest)}, - { 211, -1, -1, sizeof(::mavsdk::rpc::camera::ModeResponse)}, - { 220, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest)}, - { 228, 237, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, - { 238, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, - { 246, 255, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, - { 256, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, - { 264, 273, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, - { 274, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, - { 282, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, - { 291, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, - { 299, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, - { 308, 317, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, - { 318, 327, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, - { 328, 337, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, - { 338, 348, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, - { 350, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, - { 358, 367, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, - { 368, 377, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, - { 378, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, - { 387, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, - { 397, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, - { 409, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, - { 421, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, - { 432, 447, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, - { 454, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, - { 469, 480, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, - { 483, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, - { 501, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, - { 511, 523, -1, sizeof(::mavsdk::rpc::camera::Setting)}, - { 527, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, - { 539, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + { 118, 127, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingResponse)}, + { 128, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingRequest)}, + { 137, 146, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingResponse)}, + { 147, -1, -1, sizeof(::mavsdk::rpc::camera::SetModeRequest)}, + { 156, 165, -1, sizeof(::mavsdk::rpc::camera::SetModeResponse)}, + { 166, -1, -1, sizeof(::mavsdk::rpc::camera::ListPhotosRequest)}, + { 175, 185, -1, sizeof(::mavsdk::rpc::camera::ListPhotosResponse)}, + { 187, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeInformationRequest)}, + { 195, 204, -1, sizeof(::mavsdk::rpc::camera::InformationResponse)}, + { 205, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeModeRequest)}, + { 213, -1, -1, sizeof(::mavsdk::rpc::camera::ModeResponse)}, + { 222, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest)}, + { 230, 239, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, + { 240, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, + { 248, 257, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, + { 258, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, + { 266, 275, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, + { 276, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, + { 284, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, + { 293, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, + { 301, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, + { 310, 319, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, + { 320, 329, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, + { 330, 339, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, + { 340, 350, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, + { 352, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, + { 360, 369, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, + { 370, 379, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, + { 380, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, + { 389, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, + { 399, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, + { 411, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, + { 423, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, + { 434, 449, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, + { 456, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, + { 471, 482, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, + { 485, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, + { 503, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, + { 513, 525, -1, sizeof(::mavsdk::rpc::camera::Setting)}, + { 529, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, + { 541, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1648,181 +1656,182 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult\"" "\022\n\020StopVideoRequest\"K\n\021StopVideoResponse" "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" - "era.CameraResult\"\034\n\032StartVideoStreamingR" - "equest\"U\n\033StartVideoStreamingResponse\0226\n" - "\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.camera" - ".CameraResult\"\033\n\031StopVideoStreamingReque" - "st\"T\n\032StopVideoStreamingResponse\0226\n\rcame" - "ra_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Came" - "raResult\"7\n\016SetModeRequest\022%\n\004mode\030\001 \001(\016" - "2\027.mavsdk.rpc.camera.Mode\"I\n\017SetModeResp" - "onse\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc" - ".camera.CameraResult\"I\n\021ListPhotosReques" - "t\0224\n\014photos_range\030\001 \001(\0162\036.mavsdk.rpc.cam" - "era.PhotosRange\"\203\001\n\022ListPhotosResponse\0226" - "\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.camer" - "a.CameraResult\0225\n\rcapture_infos\030\002 \003(\0132\036." - "mavsdk.rpc.camera.CaptureInfo\"\035\n\033Subscri" - "beInformationRequest\"J\n\023InformationRespo" - "nse\0223\n\013information\030\001 \001(\0132\036.mavsdk.rpc.ca" - "mera.Information\"\026\n\024SubscribeModeRequest" - "\"5\n\014ModeResponse\022%\n\004mode\030\001 \001(\0162\027.mavsdk." - "rpc.camera.Mode\"!\n\037SubscribeVideoStreamI" - "nfoRequest\"X\n\027VideoStreamInfoResponse\022=\n" - "\021video_stream_info\030\001 \001(\0132\".mavsdk.rpc.ca" - "mera.VideoStreamInfo\"\035\n\033SubscribeCapture" - "InfoRequest\"K\n\023CaptureInfoResponse\0224\n\014ca" - "pture_info\030\001 \001(\0132\036.mavsdk.rpc.camera.Cap" - "tureInfo\"\030\n\026SubscribeStatusRequest\"B\n\016St" - "atusResponse\0220\n\rcamera_status\030\001 \001(\0132\031.ma" - "vsdk.rpc.camera.Status\"!\n\037SubscribeCurre" - "ntSettingsRequest\"O\n\027CurrentSettingsResp" - "onse\0224\n\020current_settings\030\001 \003(\0132\032.mavsdk." - "rpc.camera.Setting\"(\n&SubscribePossibleS" - "ettingOptionsRequest\"\\\n\036PossibleSettingO" - "ptionsResponse\022:\n\017setting_options\030\001 \003(\0132" - "!.mavsdk.rpc.camera.SettingOptions\"@\n\021Se" - "tSettingRequest\022+\n\007setting\030\001 \001(\0132\032.mavsd" - "k.rpc.camera.Setting\"L\n\022SetSettingRespon" + "era.CameraResult\"/\n\032StartVideoStreamingR" + "equest\022\021\n\tstream_id\030\001 \001(\005\"U\n\033StartVideoS" + "treamingResponse\0226\n\rcamera_result\030\001 \001(\0132" + "\037.mavsdk.rpc.camera.CameraResult\".\n\031Stop" + "VideoStreamingRequest\022\021\n\tstream_id\030\001 \001(\005" + "\"T\n\032StopVideoStreamingResponse\0226\n\rcamera" + "_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Camera" + "Result\"7\n\016SetModeRequest\022%\n\004mode\030\001 \001(\0162\027" + ".mavsdk.rpc.camera.Mode\"I\n\017SetModeRespon" "se\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.c" - "amera.CameraResult\"@\n\021GetSettingRequest\022" - "+\n\007setting\030\001 \001(\0132\032.mavsdk.rpc.camera.Set" - "ting\"y\n\022GetSettingResponse\0226\n\rcamera_res" - "ult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResu" - "lt\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera." - "Setting\"\026\n\024FormatStorageRequest\"O\n\025Forma" - "tStorageResponse\0226\n\rcamera_result\030\001 \001(\0132" - "\037.mavsdk.rpc.camera.CameraResult\"N\n\024Sele" - "ctCameraResponse\0226\n\rcamera_result\030\001 \001(\0132" - "\037.mavsdk.rpc.camera.CameraResult\"(\n\023Sele" - "ctCameraRequest\022\021\n\tcamera_id\030\001 \001(\005\"\301\002\n\014C" - "ameraResult\0226\n\006result\030\001 \001(\0162&.mavsdk.rpc" - ".camera.CameraResult.Result\022\022\n\nresult_st" - "r\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022" - "\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS" - "\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020" - "\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025" - "RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYS" - "TEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020\t\"q" - "\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlong" - "itude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003" - " \001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\nQua" - "ternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002" - "\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg\030\001 " - "\001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001(\002\"" - "\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.mavs" - "dk.rpc.camera.Position\022:\n\023attitude_quate" - "rnion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quaterni" - "on\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.mavsd" - "k.rpc.camera.EulerAngle\022\023\n\013time_utc_us\030\004" - " \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001(\005\022" - "\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSetting" - "s\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizontal_r" - "esolution_pix\030\002 \001(\r\022\037\n\027vertical_resoluti" - "on_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n\014ro" - "tation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022horizon" - "tal_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo\0228\n" - "\010settings\030\001 \001(\0132&.mavsdk.rpc.camera.Vide" - "oStreamSettings\022D\n\006status\030\002 \001(\01624.mavsdk" - ".rpc.camera.VideoStreamInfo.VideoStreamS" - "tatus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc.cam" - "era.VideoStreamInfo.VideoStreamSpectrum\"" - "]\n\021VideoStreamStatus\022#\n\037VIDEO_STREAM_STA" - "TUS_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STATUS" - "_IN_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!" - "\n\035VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VID" - "EO_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VI" - "DEO_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006Statu" - "s\022\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval_on" - "\030\002 \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025avai" - "lable_storage_mib\030\004 \001(\002\022\031\n\021total_storage" - "_mib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022\031\n\021" - "media_folder_name\030\007 \001(\t\022\?\n\016storage_statu" - "s\030\010 \001(\0162\'.mavsdk.rpc.camera.Status.Stora" - "geStatus\022\022\n\nstorage_id\030\t \001(\r\022;\n\014storage_" - "type\030\n \001(\0162%.mavsdk.rpc.camera.Status.St" - "orageType\"\221\001\n\rStorageStatus\022 \n\034STORAGE_S" - "TATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_" - "UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTE" - "D\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001" - "\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022" - "\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_T" - "YPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017ST" - "ORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001" - "\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022option_" - "description\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetting_" - "id\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t\022)\n" - "\006option\030\003 \001(\0132\031.mavsdk.rpc.camera.Option" - "\022\020\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022\022\n\n" - "setting_id\030\001 \001(\t\022\033\n\023setting_description\030" - "\002 \001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.came" - "ra.Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Informat" - "ion\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002" - " \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizon" - "tal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_sen" - "sor_size_mm\030\005 \001(\002\022 \n\030horizontal_resoluti" - "on_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 " - "\001(\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PH" - "OTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022\024\n\020" - "PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SINCE" - "_CONNECTION\020\0012\323\021\n\rCameraService\022R\n\007Prepa" - "re\022!.mavsdk.rpc.camera.PrepareRequest\032\"." - "mavsdk.rpc.camera.PrepareResponse\"\000\022X\n\tT" - "akePhoto\022#.mavsdk.rpc.camera.TakePhotoRe" - "quest\032$.mavsdk.rpc.camera.TakePhotoRespo" - "nse\"\000\022s\n\022StartPhotoInterval\022,.mavsdk.rpc" - ".camera.StartPhotoIntervalRequest\032-.mavs" - "dk.rpc.camera.StartPhotoIntervalResponse" - "\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.rpc.cam" - "era.StopPhotoIntervalRequest\032,.mavsdk.rp" - "c.camera.StopPhotoIntervalResponse\"\000\022[\n\n" - "StartVideo\022$.mavsdk.rpc.camera.StartVide" - "oRequest\032%.mavsdk.rpc.camera.StartVideoR" - "esponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.came" - "ra.StopVideoRequest\032$.mavsdk.rpc.camera." - "StopVideoResponse\"\000\022z\n\023StartVideoStreami" - "ng\022-.mavsdk.rpc.camera.StartVideoStreami" - "ngRequest\032..mavsdk.rpc.camera.StartVideo" - "StreamingResponse\"\004\200\265\030\001\022w\n\022StopVideoStre" - "aming\022,.mavsdk.rpc.camera.StopVideoStrea" - "mingRequest\032-.mavsdk.rpc.camera.StopVide" - "oStreamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!.ma" - "vsdk.rpc.camera.SetModeRequest\032\".mavsdk." - "rpc.camera.SetModeResponse\"\000\022[\n\nListPhot" - "os\022$.mavsdk.rpc.camera.ListPhotosRequest" - "\032%.mavsdk.rpc.camera.ListPhotosResponse\"" - "\000\022]\n\rSubscribeMode\022\'.mavsdk.rpc.camera.S" - "ubscribeModeRequest\032\037.mavsdk.rpc.camera." - "ModeResponse\"\0000\001\022r\n\024SubscribeInformation" - "\022..mavsdk.rpc.camera.SubscribeInformatio" - "nRequest\032&.mavsdk.rpc.camera.Information" - "Response\"\0000\001\022~\n\030SubscribeVideoStreamInfo" - "\0222.mavsdk.rpc.camera.SubscribeVideoStrea" - "mInfoRequest\032*.mavsdk.rpc.camera.VideoSt" - "reamInfoResponse\"\0000\001\022v\n\024SubscribeCapture" - "Info\022..mavsdk.rpc.camera.SubscribeCaptur" - "eInfoRequest\032&.mavsdk.rpc.camera.Capture" - "InfoResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStatus\022" - ").mavsdk.rpc.camera.SubscribeStatusReque" - "st\032!.mavsdk.rpc.camera.StatusResponse\"\0000" - "\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavsdk." - "rpc.camera.SubscribeCurrentSettingsReque" - "st\032*.mavsdk.rpc.camera.CurrentSettingsRe" - "sponse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleSett" - "ingOptions\0229.mavsdk.rpc.camera.Subscribe" - "PossibleSettingOptionsRequest\0321.mavsdk.r" - "pc.camera.PossibleSettingOptionsResponse" - "\"\0000\001\022[\n\nSetSetting\022$.mavsdk.rpc.camera.S" - "etSettingRequest\032%.mavsdk.rpc.camera.Set" - "SettingResponse\"\000\022[\n\nGetSetting\022$.mavsdk" - ".rpc.camera.GetSettingRequest\032%.mavsdk.r" - "pc.camera.GetSettingResponse\"\000\022d\n\rFormat" - "Storage\022\'.mavsdk.rpc.camera.FormatStorag" - "eRequest\032(.mavsdk.rpc.camera.FormatStora" - "geResponse\"\000\022e\n\014SelectCamera\022&.mavsdk.rp" - "c.camera.SelectCameraRequest\032\'.mavsdk.rp" - "c.camera.SelectCameraResponse\"\004\200\265\030\001B\037\n\020i" - "o.mavsdk.cameraB\013CameraProtob\006proto3" + "amera.CameraResult\"I\n\021ListPhotosRequest\022" + "4\n\014photos_range\030\001 \001(\0162\036.mavsdk.rpc.camer" + "a.PhotosRange\"\203\001\n\022ListPhotosResponse\0226\n\r" + "camera_result\030\001 \001(\0132\037.mavsdk.rpc.camera." + "CameraResult\0225\n\rcapture_infos\030\002 \003(\0132\036.ma" + "vsdk.rpc.camera.CaptureInfo\"\035\n\033Subscribe" + "InformationRequest\"J\n\023InformationRespons" + "e\0223\n\013information\030\001 \001(\0132\036.mavsdk.rpc.came" + "ra.Information\"\026\n\024SubscribeModeRequest\"5" + "\n\014ModeResponse\022%\n\004mode\030\001 \001(\0162\027.mavsdk.rp" + "c.camera.Mode\"!\n\037SubscribeVideoStreamInf" + "oRequest\"X\n\027VideoStreamInfoResponse\022=\n\021v" + "ideo_stream_info\030\001 \001(\0132\".mavsdk.rpc.came" + "ra.VideoStreamInfo\"\035\n\033SubscribeCaptureIn" + "foRequest\"K\n\023CaptureInfoResponse\0224\n\014capt" + "ure_info\030\001 \001(\0132\036.mavsdk.rpc.camera.Captu" + "reInfo\"\030\n\026SubscribeStatusRequest\"B\n\016Stat" + "usResponse\0220\n\rcamera_status\030\001 \001(\0132\031.mavs" + "dk.rpc.camera.Status\"!\n\037SubscribeCurrent" + "SettingsRequest\"O\n\027CurrentSettingsRespon" + "se\0224\n\020current_settings\030\001 \003(\0132\032.mavsdk.rp" + "c.camera.Setting\"(\n&SubscribePossibleSet" + "tingOptionsRequest\"\\\n\036PossibleSettingOpt" + "ionsResponse\022:\n\017setting_options\030\001 \003(\0132!." + "mavsdk.rpc.camera.SettingOptions\"@\n\021SetS" + "ettingRequest\022+\n\007setting\030\001 \001(\0132\032.mavsdk." + "rpc.camera.Setting\"L\n\022SetSettingResponse" + "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" + "era.CameraResult\"@\n\021GetSettingRequest\022+\n" + "\007setting\030\001 \001(\0132\032.mavsdk.rpc.camera.Setti" + "ng\"y\n\022GetSettingResponse\0226\n\rcamera_resul" + "t\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult" + "\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera.Se" + "tting\"\026\n\024FormatStorageRequest\"O\n\025FormatS" + "torageResponse\0226\n\rcamera_result\030\001 \001(\0132\037." + "mavsdk.rpc.camera.CameraResult\"N\n\024Select" + "CameraResponse\0226\n\rcamera_result\030\001 \001(\0132\037." + "mavsdk.rpc.camera.CameraResult\"(\n\023Select" + "CameraRequest\022\021\n\tcamera_id\030\001 \001(\005\"\301\002\n\014Cam" + "eraResult\0226\n\006result\030\001 \001(\0162&.mavsdk.rpc.c" + "amera.CameraResult.Result\022\022\n\nresult_str\030" + "\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" + "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" + "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" + "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" + "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" + "M\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020\t\"q\n\010" + "Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongit" + "ude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001" + "(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\nQuate" + "rnion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t" + "\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg\030\001 \001(" + "\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001(\002\"\377\001" + "\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.mavsdk" + ".rpc.camera.Position\022:\n\023attitude_quatern" + "ion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quaternion" + "\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.mavsdk." + "rpc.camera.EulerAngle\022\023\n\013time_utc_us\030\004 \001" + "(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001(\005\022\020\n" + "\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSettings\022" + "\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizontal_res" + "olution_pix\030\002 \001(\r\022\037\n\027vertical_resolution" + "_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n\014rota" + "tion_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022horizonta" + "l_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo\0228\n\010s" + "ettings\030\001 \001(\0132&.mavsdk.rpc.camera.VideoS" + "treamSettings\022D\n\006status\030\002 \001(\01624.mavsdk.r" + "pc.camera.VideoStreamInfo.VideoStreamSta" + "tus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc.camer" + "a.VideoStreamInfo.VideoStreamSpectrum\"]\n" + "\021VideoStreamStatus\022#\n\037VIDEO_STREAM_STATU" + "S_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STATUS_I" + "N_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!\n\035" + "VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VIDEO" + "_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VIDE" + "O_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006Status\022" + "\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval_on\030\002" + " \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025availa" + "ble_storage_mib\030\004 \001(\002\022\031\n\021total_storage_m" + "ib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022\031\n\021me" + "dia_folder_name\030\007 \001(\t\022\?\n\016storage_status\030" + "\010 \001(\0162\'.mavsdk.rpc.camera.Status.Storage" + "Status\022\022\n\nstorage_id\030\t \001(\r\022;\n\014storage_ty" + "pe\030\n \001(\0162%.mavsdk.rpc.camera.Status.Stor" + "ageType\"\221\001\n\rStorageStatus\022 \n\034STORAGE_STA" + "TUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_UN" + "FORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTED\020" + "\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001\n\013" + "StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022\032\n" + "\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_TYP" + "E_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017STOR" + "AGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001\"7" + "\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022option_de" + "scription\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetting_id" + "\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t\022)\n\006o" + "ption\030\003 \001(\0132\031.mavsdk.rpc.camera.Option\022\020" + "\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022\022\n\nse" + "tting_id\030\001 \001(\t\022\033\n\023setting_description\030\002 " + "\001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.camera" + ".Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Informatio" + "n\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001" + "(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizonta" + "l_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_senso" + "r_size_mm\030\005 \001(\002\022 \n\030horizontal_resolution" + "_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 \001(" + "\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHOT" + "O\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022\024\n\020PH" + "OTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SINCE_C" + "ONNECTION\020\0012\323\021\n\rCameraService\022R\n\007Prepare" + "\022!.mavsdk.rpc.camera.PrepareRequest\032\".ma" + "vsdk.rpc.camera.PrepareResponse\"\000\022X\n\tTak" + "ePhoto\022#.mavsdk.rpc.camera.TakePhotoRequ" + "est\032$.mavsdk.rpc.camera.TakePhotoRespons" + "e\"\000\022s\n\022StartPhotoInterval\022,.mavsdk.rpc.c" + "amera.StartPhotoIntervalRequest\032-.mavsdk" + ".rpc.camera.StartPhotoIntervalResponse\"\000" + "\022p\n\021StopPhotoInterval\022+.mavsdk.rpc.camer" + "a.StopPhotoIntervalRequest\032,.mavsdk.rpc." + "camera.StopPhotoIntervalResponse\"\000\022[\n\nSt" + "artVideo\022$.mavsdk.rpc.camera.StartVideoR" + "equest\032%.mavsdk.rpc.camera.StartVideoRes" + "ponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.camera" + ".StopVideoRequest\032$.mavsdk.rpc.camera.St" + "opVideoResponse\"\000\022z\n\023StartVideoStreaming" + "\022-.mavsdk.rpc.camera.StartVideoStreaming" + "Request\032..mavsdk.rpc.camera.StartVideoSt" + "reamingResponse\"\004\200\265\030\001\022w\n\022StopVideoStream" + "ing\022,.mavsdk.rpc.camera.StopVideoStreami" + "ngRequest\032-.mavsdk.rpc.camera.StopVideoS" + "treamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!.mavs" + "dk.rpc.camera.SetModeRequest\032\".mavsdk.rp" + "c.camera.SetModeResponse\"\000\022[\n\nListPhotos" + "\022$.mavsdk.rpc.camera.ListPhotosRequest\032%" + ".mavsdk.rpc.camera.ListPhotosResponse\"\000\022" + "]\n\rSubscribeMode\022\'.mavsdk.rpc.camera.Sub" + "scribeModeRequest\032\037.mavsdk.rpc.camera.Mo" + "deResponse\"\0000\001\022r\n\024SubscribeInformation\022." + ".mavsdk.rpc.camera.SubscribeInformationR" + "equest\032&.mavsdk.rpc.camera.InformationRe" + "sponse\"\0000\001\022~\n\030SubscribeVideoStreamInfo\0222" + ".mavsdk.rpc.camera.SubscribeVideoStreamI" + "nfoRequest\032*.mavsdk.rpc.camera.VideoStre" + "amInfoResponse\"\0000\001\022v\n\024SubscribeCaptureIn" + "fo\022..mavsdk.rpc.camera.SubscribeCaptureI" + "nfoRequest\032&.mavsdk.rpc.camera.CaptureIn" + "foResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStatus\022)." + "mavsdk.rpc.camera.SubscribeStatusRequest" + "\032!.mavsdk.rpc.camera.StatusResponse\"\0000\001\022" + "\202\001\n\030SubscribeCurrentSettings\0222.mavsdk.rp" + "c.camera.SubscribeCurrentSettingsRequest" + "\032*.mavsdk.rpc.camera.CurrentSettingsResp" + "onse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleSettin" + "gOptions\0229.mavsdk.rpc.camera.SubscribePo" + "ssibleSettingOptionsRequest\0321.mavsdk.rpc" + ".camera.PossibleSettingOptionsResponse\"\000" + "0\001\022[\n\nSetSetting\022$.mavsdk.rpc.camera.Set" + "SettingRequest\032%.mavsdk.rpc.camera.SetSe" + "ttingResponse\"\000\022[\n\nGetSetting\022$.mavsdk.r" + "pc.camera.GetSettingRequest\032%.mavsdk.rpc" + ".camera.GetSettingResponse\"\000\022d\n\rFormatSt" + "orage\022\'.mavsdk.rpc.camera.FormatStorageR" + "equest\032(.mavsdk.rpc.camera.FormatStorage" + "Response\"\000\022e\n\014SelectCamera\022&.mavsdk.rpc." + "camera.SelectCameraRequest\032\'.mavsdk.rpc." + "camera.SelectCameraResponse\"\004\200\265\030\001B\037\n\020io." + "mavsdk.cameraB\013CameraProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -1832,7 +1841,7 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 7676, + 7714, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, @@ -3656,31 +3665,167 @@ class StartVideoStreamingRequest::_Internal { }; StartVideoStreamingRequest::StartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.StartVideoStreamingRequest) } StartVideoStreamingRequest::StartVideoStreamingRequest(const StartVideoStreamingRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - StartVideoStreamingRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.StartVideoStreamingRequest) } +inline void StartVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StartVideoStreamingRequest::~StartVideoStreamingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StartVideoStreamingRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StartVideoStreamingRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StartVideoStreamingRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StartVideoStreamingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.StartVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StartVideoStreamingRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StartVideoStreamingRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.StartVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera.StartVideoStreamingRequest) + return target; +} +::size_t StartVideoStreamingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.StartVideoStreamingRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoStreamingRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StartVideoStreamingRequest::MergeImpl }; const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoStreamingRequest::GetClassData() const { return &_class_data_; } +void StartVideoStreamingRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera.StartVideoStreamingRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} +void StartVideoStreamingRequest::CopyFrom(const StartVideoStreamingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.StartVideoStreamingRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +bool StartVideoStreamingRequest::IsInitialized() const { + return true; +} + +void StartVideoStreamingRequest::InternalSwap(StartVideoStreamingRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} ::PROTOBUF_NAMESPACE_ID::Metadata StartVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( @@ -3899,31 +4044,167 @@ class StopVideoStreamingRequest::_Internal { }; StopVideoStreamingRequest::StopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.StopVideoStreamingRequest) } StopVideoStreamingRequest::StopVideoStreamingRequest(const StopVideoStreamingRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - StopVideoStreamingRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.StopVideoStreamingRequest) } +inline void StopVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} +StopVideoStreamingRequest::~StopVideoStreamingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StopVideoStreamingRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} +inline void StopVideoStreamingRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} +void StopVideoStreamingRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StopVideoStreamingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.StopVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StopVideoStreamingRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StopVideoStreamingRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.StopVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera.StopVideoStreamingRequest) + return target; +} + +::size_t StopVideoStreamingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.StopVideoStreamingRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoStreamingRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StopVideoStreamingRequest::MergeImpl }; const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoStreamingRequest::GetClassData() const { return &_class_data_; } +void StopVideoStreamingRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera.StopVideoStreamingRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StopVideoStreamingRequest::CopyFrom(const StopVideoStreamingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.StopVideoStreamingRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +bool StopVideoStreamingRequest::IsInitialized() const { + return true; +} +void StopVideoStreamingRequest::InternalSwap(StopVideoStreamingRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} ::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index b9a69b9d96..f320b2a85b 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -2311,9 +2311,10 @@ class StopVideoResponse final : };// ------------------------------------------------------------------- class StartVideoStreamingRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoStreamingRequest) */ { + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoStreamingRequest) */ { public: inline StartVideoStreamingRequest() : StartVideoStreamingRequest(nullptr) {} + ~StartVideoStreamingRequest() override; template explicit PROTOBUF_CONSTEXPR StartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); @@ -2394,15 +2395,29 @@ class StartVideoStreamingRequest final : StartVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StartVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StartVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StartVideoStreamingRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StartVideoStreamingRequest& from) { + StartVideoStreamingRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StartVideoStreamingRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; @@ -2422,6 +2437,19 @@ class StartVideoStreamingRequest final : // accessors ------------------------------------------------------- + enum : int { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoStreamingRequest) private: class _Internal; @@ -2430,7 +2458,10 @@ class StartVideoStreamingRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -2595,9 +2626,10 @@ class StartVideoStreamingResponse final : };// ------------------------------------------------------------------- class StopVideoStreamingRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoStreamingRequest) */ { + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoStreamingRequest) */ { public: inline StopVideoStreamingRequest() : StopVideoStreamingRequest(nullptr) {} + ~StopVideoStreamingRequest() override; template explicit PROTOBUF_CONSTEXPR StopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); @@ -2678,15 +2710,29 @@ class StopVideoStreamingRequest final : StopVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StopVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StopVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StopVideoStreamingRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StopVideoStreamingRequest& from) { + StopVideoStreamingRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StopVideoStreamingRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; @@ -2706,6 +2752,19 @@ class StopVideoStreamingRequest final : // accessors ------------------------------------------------------- + enum : int { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopVideoStreamingRequest) private: class _Internal; @@ -2714,7 +2773,10 @@ class StopVideoStreamingRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -10052,6 +10114,26 @@ inline void StopVideoResponse::set_allocated_camera_result(::mavsdk::rpc::camera // StartVideoStreamingRequest +// int32 stream_id = 1; +inline void StartVideoStreamingRequest::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StartVideoStreamingRequest::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.StartVideoStreamingRequest.stream_id) + return _internal_stream_id(); +} +inline void StartVideoStreamingRequest::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.StartVideoStreamingRequest.stream_id) +} +inline ::int32_t StartVideoStreamingRequest::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StartVideoStreamingRequest::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + // ------------------------------------------------------------------- // StartVideoStreamingResponse @@ -10147,6 +10229,26 @@ inline void StartVideoStreamingResponse::set_allocated_camera_result(::mavsdk::r // StopVideoStreamingRequest +// int32 stream_id = 1; +inline void StopVideoStreamingRequest::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StopVideoStreamingRequest::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.StopVideoStreamingRequest.stream_id) + return _internal_stream_id(); +} +inline void StopVideoStreamingRequest::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.StopVideoStreamingRequest.stream_id) +} +inline ::int32_t StopVideoStreamingRequest::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StopVideoStreamingRequest::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + // ------------------------------------------------------------------- // StopVideoStreamingResponse diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index d77a8f3eb1..b4e353f361 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -30,6 +30,8 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -45,6 +47,8 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -164,6 +168,38 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* Cam return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* CameraServerService::Stub::SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(channel_.get(), rpcmethod_SubscribeStartVideoStreaming_, context, request); +} + +void CameraServerService::Stub::async::SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStartVideoStreaming_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* CameraServerService::Stub::AsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideoStreaming_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideoStreaming_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* CameraServerService::Stub::SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), rpcmethod_SubscribeStopVideoStreaming_, context, request); +} + +void CameraServerService::Stub::async::SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStopVideoStreaming_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* CameraServerService::Stub::AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideoStreaming_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideoStreaming_, context, request, false, nullptr); +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -225,6 +261,26 @@ CameraServerService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { return service->SubscribeStopVideo(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[6], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer) { + return service->SubscribeStartVideoStreaming(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[7], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer) { + return service->SubscribeStopVideoStreaming(ctx, req, writer); + }, this))); } CameraServerService::Service::~Service() { @@ -272,6 +328,20 @@ ::grpc::Status CameraServerService::Service::SubscribeStopVideo(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index 925d9fa82d..afd86c192e 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -92,6 +92,26 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); } + // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(SubscribeStartVideoStreamingRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> AsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(AsyncSubscribeStartVideoStreamingRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> PrepareAsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(PrepareAsyncSubscribeStartVideoStreamingRaw(context, request, cq)); + } + // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(SubscribeStopVideoStreamingRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> AsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(AsyncSubscribeStopVideoStreamingRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -110,6 +130,10 @@ class CameraServerService final { virtual void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) = 0; // Subscribe to stop video requests. Each request received should response to using StopVideoResponse virtual void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) = 0; + // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + virtual void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) = 0; + // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + virtual void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -130,6 +154,12 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* AsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* PrepareAsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -182,6 +212,24 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(SubscribeStartVideoStreamingRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> AsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(AsyncSubscribeStartVideoStreamingRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> PrepareAsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(PrepareAsyncSubscribeStartVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(SubscribeStopVideoStreamingRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> AsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(AsyncSubscribeStopVideoStreamingRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -194,6 +242,8 @@ class CameraServerService final { void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) override; void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) override; + void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) override; + void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -220,12 +270,20 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* AsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* PrepareAsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideo_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideoStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideoStreaming_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -245,6 +303,10 @@ class CameraServerService final { virtual ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer); // Subscribe to stop video requests. Each request received should response to using StopVideoResponse virtual ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer); + // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + virtual ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer); + // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + virtual ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -366,7 +428,47 @@ class CameraServerService final { ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodAsync(6); + } + ~WithAsyncMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodAsync(7); + } + ~WithAsyncMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -514,7 +616,51 @@ class CameraServerService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideo( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > CallbackService; + template + class WithCallbackMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request) { return this->SubscribeStartVideoStreaming(context, request); })); + } + ~WithCallbackMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* SubscribeStartVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodCallback(7, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request) { return this->SubscribeStopVideoStreaming(context, request); })); + } + ~WithCallbackMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -619,6 +765,40 @@ class CameraServerService final { } }; template + class WithGenericMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodGeneric(6); + } + ~WithGenericMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodGeneric(7); + } + ~WithGenericMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -739,6 +919,46 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodRaw(6); + } + ~WithRawMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodRaw(7); + } + ~WithRawMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -871,6 +1091,50 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodRawCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideoStreaming(context, request); })); + } + ~WithRawCallbackMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStartVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodRawCallback(7, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideoStreaming(context, request); })); + } + ~WithRawCallbackMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStopVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1033,8 +1297,62 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest,::mavsdk::rpc::camera_server::StopVideoResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeStartVideoStreaming() { + ::grpc::Service::MarkMethodStreamed(6, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* streamer) { + return this->StreamedSubscribeStartVideoStreaming(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest,::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeStopVideoStreaming() { + ::grpc::Service::MarkMethodStreamed(7, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* streamer) { + return this->StreamedSubscribeStopVideoStreaming(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest,::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index c544e417c9..836c858cd0 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -173,6 +173,64 @@ struct StopVideoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeStartVideoStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeStartVideoStreamingRequestDefaultTypeInternal() {} + union { + SubscribeStartVideoStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStartVideoStreamingRequestDefaultTypeInternal _SubscribeStartVideoStreamingRequest_default_instance_; +template +PROTOBUF_CONSTEXPR StartVideoStreamingResponse::StartVideoStreamingResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StartVideoStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StartVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StartVideoStreamingResponseDefaultTypeInternal() {} + union { + StartVideoStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoStreamingResponseDefaultTypeInternal _StartVideoStreamingResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeStopVideoStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeStopVideoStreamingRequestDefaultTypeInternal() {} + union { + SubscribeStopVideoStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStopVideoStreamingRequestDefaultTypeInternal _SubscribeStopVideoStreamingRequest_default_instance_; +template +PROTOBUF_CONSTEXPR StopVideoStreamingResponse::StopVideoStreamingResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stream_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StopVideoStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StopVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StopVideoStreamingResponseDefaultTypeInternal() {} + union { + StopVideoStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; +template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -344,7 +402,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -440,6 +498,40 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, _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::camera_server::StartVideoStreamingResponse, _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::camera_server::StartVideoStreamingResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, _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::camera_server::StopVideoStreamingResponse, _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::camera_server::StopVideoStreamingResponse, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -549,13 +641,17 @@ static const ::_pbi::MigrationSchema { 64, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, { 73, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, { 81, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, - { 90, 100, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 102, 111, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 112, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 131, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 143, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 155, 169, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 175, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 90, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, + { 98, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, + { 107, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, + { 115, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, + { 124, 134, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 136, 145, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 146, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 165, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 177, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 189, 203, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 209, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -569,6 +665,10 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_StartVideoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStopVideoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StopVideoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeStartVideoStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StartVideoStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeStopVideoStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StopVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -593,64 +693,76 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\005\"\034\n\032SubscribeStartVideoRequest\"\'\n\022Start" "VideoResponse\022\021\n\tstream_id\030\001 \001(\005\"\033\n\031Subs" "cribeStopVideoRequest\"&\n\021StopVideoRespon" - "se\022\021\n\tstream_id\030\001 \001(\005\"\240\001\n\027RespondTakePho" - "toRequest\022H\n\023take_photo_feedback\030\001 \001(\0162+" - ".mavsdk.rpc.camera_server.TakePhotoFeedb" - "ack\022;\n\014capture_info\030\002 \001(\0132%.mavsdk.rpc.c" - "amera_server.CaptureInfo\"f\n\030RespondTakeP" - "hotoResponse\022J\n\024camera_server_result\030\001 \001" - "(\0132,.mavsdk.rpc.camera_server.CameraServ" - "erResult\"\276\002\n\013Information\022\023\n\013vendor_name\030" - "\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\030\n\020firmware_ve" - "rsion\030\003 \001(\t\022\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031" - "horizontal_sensor_size_mm\030\005 \001(\002\022\037\n\027verti" - "cal_sensor_size_mm\030\006 \001(\002\022 \n\030horizontal_r" - "esolution_px\030\007 \001(\r\022\036\n\026vertical_resolutio" - "n_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(\r\022\037\n\027definitio" - "n_file_version\030\n \001(\r\022\033\n\023definition_file_" - "uri\030\013 \001(\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 " - "\001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_a" - "ltitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004" - " \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002" - "\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224" - "\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_ser" - "ver.Position\022A\n\023attitude_quaternion\030\002 \001(" - "\0132$.mavsdk.rpc.camera_server.Quaternion\022" - "\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010" - "\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Ca" - "meraServerResult\022C\n\006result\030\001 \001(\01623.mavsd" - "k.rpc.camera_server.CameraServerResult.R" - "esult\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016" - "RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022" - "RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n" - "\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RE" - "SULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020" - "\007\022\024\n\020RESULT_NO_SYSTEM\020\010*\216\001\n\021TakePhotoFee" - "dback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032" - "\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO" - "_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_" - "FAILED\020\0032\215\006\n\023CameraServerService\022y\n\016SetI" - "nformation\022/.mavsdk.rpc.camera_server.Se" - "tInformationRequest\0320.mavsdk.rpc.camera_" - "server.SetInformationResponse\"\004\200\265\030\001\022v\n\rS" - "etInProgress\022..mavsdk.rpc.camera_server." - "SetInProgressRequest\032/.mavsdk.rpc.camera" - "_server.SetInProgressResponse\"\004\200\265\030\001\022~\n\022S" - "ubscribeTakePhoto\0223.mavsdk.rpc.camera_se" - "rver.SubscribeTakePhotoRequest\032+.mavsdk." - "rpc.camera_server.TakePhotoResponse\"\004\200\265\030" - "\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.rpc.cam" - "era_server.RespondTakePhotoRequest\0322.mav" - "sdk.rpc.camera_server.RespondTakePhotoRe" - "sponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVideo\0224.m" - "avsdk.rpc.camera_server.SubscribeStartVi" - "deoRequest\032,.mavsdk.rpc.camera_server.St" - "artVideoResponse\"\004\200\265\030\0000\001\022~\n\022SubscribeSto" - "pVideo\0223.mavsdk.rpc.camera_server.Subscr" - "ibeStopVideoRequest\032+.mavsdk.rpc.camera_" - "server.StopVideoResponse\"\004\200\265\030\0000\001B,\n\027io.m" - "avsdk.camera_serverB\021CameraServerProtob\006" - "proto3" + "se\022\021\n\tstream_id\030\001 \001(\005\"%\n#SubscribeStartV" + "ideoStreamingRequest\"0\n\033StartVideoStream" + "ingResponse\022\021\n\tstream_id\030\001 \001(\005\"$\n\"Subscr" + "ibeStopVideoStreamingRequest\"/\n\032StopVide" + "oStreamingResponse\022\021\n\tstream_id\030\001 \001(\005\"\240\001" + "\n\027RespondTakePhotoRequest\022H\n\023take_photo_" + "feedback\030\001 \001(\0162+.mavsdk.rpc.camera_serve" + "r.TakePhotoFeedback\022;\n\014capture_info\030\002 \001(" + "\0132%.mavsdk.rpc.camera_server.CaptureInfo" + "\"f\n\030RespondTakePhotoResponse\022J\n\024camera_s" + "erver_result\030\001 \001(\0132,.mavsdk.rpc.camera_s" + "erver.CameraServerResult\"\276\002\n\013Information" + "\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(" + "\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal_len" + "gth_mm\030\004 \001(\002\022!\n\031horizontal_sensor_size_m" + "m\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006 \001(\002" + "\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036\n\026ve" + "rtical_resolution_px\030\010 \001(\r\022\017\n\007lens_id\030\t " + "\001(\r\022\037\n\027definition_file_version\030\n \001(\r\022\033\n\023" + "definition_file_uri\030\013 \001(\t\"q\n\010Position\022\024\n" + "\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001" + "(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023relat" + "ive_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030" + "\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320" + "\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".mavsd" + "k.rpc.camera_server.Position\022A\n\023attitude" + "_quaternion\030\002 \001(\0132$.mavsdk.rpc.camera_se" + "rver.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\n" + "is_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_" + "url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006resu" + "lt\030\001 \001(\01623.mavsdk.rpc.camera_server.Came" + "raServerResult.Result\022\022\n\nresult_str\030\002 \001(" + "\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESU" + "LT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013" + "RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESU" + "LT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT" + "_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010*" + "\216\001\n\021TakePhotoFeedback\022\037\n\033TAKE_PHOTO_FEED" + "BACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK" + "\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE" + "_PHOTO_FEEDBACK_FAILED\020\0032\310\010\n\023CameraServe" + "rService\022y\n\016SetInformation\022/.mavsdk.rpc." + "camera_server.SetInformationRequest\0320.ma" + "vsdk.rpc.camera_server.SetInformationRes" + "ponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rp" + "c.camera_server.SetInProgressRequest\032/.m" + "avsdk.rpc.camera_server.SetInProgressRes" + "ponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavs" + "dk.rpc.camera_server.SubscribeTakePhotoR" + "equest\032+.mavsdk.rpc.camera_server.TakePh" + "otoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\022" + "1.mavsdk.rpc.camera_server.RespondTakePh" + "otoRequest\0322.mavsdk.rpc.camera_server.Re" + "spondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023Subscri" + "beStartVideo\0224.mavsdk.rpc.camera_server." + "SubscribeStartVideoRequest\032,.mavsdk.rpc." + "camera_server.StartVideoResponse\"\004\200\265\030\0000\001" + "\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.came" + "ra_server.SubscribeStopVideoRequest\032+.ma" + "vsdk.rpc.camera_server.StopVideoResponse" + "\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideoStreamin" + "g\022=.mavsdk.rpc.camera_server.SubscribeSt" + "artVideoStreamingRequest\0325.mavsdk.rpc.ca" + "mera_server.StartVideoStreamingResponse\"" + "\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoStreaming\022" + "<.mavsdk.rpc.camera_server.SubscribeStop" + "VideoStreamingRequest\0324.mavsdk.rpc.camer" + "a_server.StopVideoStreamingResponse\"\004\200\265\030" + "\0000\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" + "rverProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -660,13 +772,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 2886, + 3377, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 17, + 21, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -2174,6 +2286,430 @@ ::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { } // =================================================================== +class SubscribeStartVideoStreamingRequest::_Internal { + public: +}; + +SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) +} +SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStartVideoStreamingRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); +} +// =================================================================== + +class StartVideoStreamingResponse::_Internal { + public: +}; + +StartVideoStreamingResponse::StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +} +StartVideoStreamingResponse::StartVideoStreamingResponse(const StartVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +} + +inline void StartVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StartVideoStreamingResponse::~StartVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StartVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StartVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StartVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StartVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StartVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StartVideoStreamingResponse) + return target; +} + +::size_t StartVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StartVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void StartVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StartVideoStreamingResponse::CopyFrom(const StartVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StartVideoStreamingResponse::IsInitialized() const { + return true; +} + +void StartVideoStreamingResponse::InternalSwap(StartVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StartVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); +} +// =================================================================== + +class SubscribeStopVideoStreamingRequest::_Internal { + public: +}; + +SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) +} +SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStopVideoStreamingRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); +} +// =================================================================== + +class StopVideoStreamingResponse::_Internal { + public: +}; + +StopVideoStreamingResponse::StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +} +StopVideoStreamingResponse::StopVideoStreamingResponse(const StopVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +} + +inline void StopVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StopVideoStreamingResponse::~StopVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StopVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StopVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StopVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StopVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StopVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StopVideoStreamingResponse) + return target; +} + +::size_t StopVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StopVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void StopVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StopVideoStreamingResponse::CopyFrom(const StopVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StopVideoStreamingResponse::IsInitialized() const { + return true; +} + +void StopVideoStreamingResponse::InternalSwap(StopVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); +} +// =================================================================== + class RespondTakePhotoRequest::_Internal { public: using HasBits = decltype(std::declval()._impl_._has_bits_); @@ -2412,7 +2948,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); } // =================================================================== @@ -2617,7 +3153,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); } // =================================================================== @@ -3202,7 +3738,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); } // =================================================================== @@ -3507,7 +4043,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); } // =================================================================== @@ -3812,7 +4348,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); } // =================================================================== @@ -4215,7 +4751,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); } // =================================================================== @@ -4444,7 +4980,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -4491,6 +5027,22 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StartVideoStreamingResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoStreamingResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index cc3322ae0c..914e39d7f1 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -92,15 +92,27 @@ extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default class StartVideoResponse; struct StartVideoResponseDefaultTypeInternal; extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; +class StartVideoStreamingResponse; +struct StartVideoStreamingResponseDefaultTypeInternal; +extern StartVideoStreamingResponseDefaultTypeInternal _StartVideoStreamingResponse_default_instance_; class StopVideoResponse; struct StopVideoResponseDefaultTypeInternal; extern StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; +class StopVideoStreamingResponse; +struct StopVideoStreamingResponseDefaultTypeInternal; +extern StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; class SubscribeStartVideoRequest; struct SubscribeStartVideoRequestDefaultTypeInternal; extern SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; +class SubscribeStartVideoStreamingRequest; +struct SubscribeStartVideoStreamingRequestDefaultTypeInternal; +extern SubscribeStartVideoStreamingRequestDefaultTypeInternal _SubscribeStartVideoStreamingRequest_default_instance_; class SubscribeStopVideoRequest; struct SubscribeStopVideoRequestDefaultTypeInternal; extern SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_default_instance_; +class SubscribeStopVideoStreamingRequest; +struct SubscribeStopVideoStreamingRequestDefaultTypeInternal; +extern SubscribeStopVideoStreamingRequestDefaultTypeInternal _SubscribeStopVideoStreamingRequest_default_instance_; class SubscribeTakePhotoRequest; struct SubscribeTakePhotoRequestDefaultTypeInternal; extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; @@ -136,12 +148,20 @@ ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage< template <> ::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::StartVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoStreamingResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::StopVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoStreamingResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); template <> +::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStopVideoRequest>(Arena*); template <> +::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); @@ -1701,6 +1721,564 @@ class StopVideoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- +class SubscribeStartVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) */ { + public: + inline SubscribeStartVideoStreamingRequest() : SubscribeStartVideoStreamingRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from); + SubscribeStartVideoStreamingRequest(SubscribeStartVideoStreamingRequest&& from) noexcept + : SubscribeStartVideoStreamingRequest() { + *this = ::std::move(from); + } + + inline SubscribeStartVideoStreamingRequest& operator=(const SubscribeStartVideoStreamingRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeStartVideoStreamingRequest& operator=(SubscribeStartVideoStreamingRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeStartVideoStreamingRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeStartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoStreamingRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeStartVideoStreamingRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeStartVideoStreamingRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeStartVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStartVideoStreamingRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStartVideoStreamingRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest"; + } + protected: + explicit SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class StartVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoStreamingResponse) */ { + public: + inline StartVideoStreamingResponse() : StartVideoStreamingResponse(nullptr) {} + ~StartVideoStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + StartVideoStreamingResponse(const StartVideoStreamingResponse& from); + StartVideoStreamingResponse(StartVideoStreamingResponse&& from) noexcept + : StartVideoStreamingResponse() { + *this = ::std::move(from); + } + + inline StartVideoStreamingResponse& operator=(const StartVideoStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline StartVideoStreamingResponse& operator=(StartVideoStreamingResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 StartVideoStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StartVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 11; + + friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(StartVideoStreamingResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(StartVideoStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StartVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StartVideoStreamingResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StartVideoStreamingResponse& from) { + StartVideoStreamingResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StartVideoStreamingResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.StartVideoStreamingResponse"; + } + protected: + explicit StartVideoStreamingResponse(::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 { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeStopVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) */ { + public: + inline SubscribeStopVideoStreamingRequest() : SubscribeStopVideoStreamingRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from); + SubscribeStopVideoStreamingRequest(SubscribeStopVideoStreamingRequest&& from) noexcept + : SubscribeStopVideoStreamingRequest() { + *this = ::std::move(from); + } + + inline SubscribeStopVideoStreamingRequest& operator=(const SubscribeStopVideoStreamingRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeStopVideoStreamingRequest& operator=(SubscribeStopVideoStreamingRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeStopVideoStreamingRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeStopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoStreamingRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 12; + + friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeStopVideoStreamingRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeStopVideoStreamingRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeStopVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStopVideoStreamingRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStopVideoStreamingRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest"; + } + protected: + explicit SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class StopVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoStreamingResponse) */ { + public: + inline StopVideoStreamingResponse() : StopVideoStreamingResponse(nullptr) {} + ~StopVideoStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + StopVideoStreamingResponse(const StopVideoStreamingResponse& from); + StopVideoStreamingResponse(StopVideoStreamingResponse&& from) noexcept + : StopVideoStreamingResponse() { + *this = ::std::move(from); + } + + inline StopVideoStreamingResponse& operator=(const StopVideoStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline StopVideoStreamingResponse& operator=(StopVideoStreamingResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 StopVideoStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const StopVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(StopVideoStreamingResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(StopVideoStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StopVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StopVideoStreamingResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StopVideoStreamingResponse& from) { + StopVideoStreamingResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StopVideoStreamingResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.StopVideoStreamingResponse"; + } + protected: + explicit StopVideoStreamingResponse(::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 { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t stream_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RespondTakePhotoRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: @@ -1757,7 +2335,7 @@ class RespondTakePhotoRequest final : &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 14; friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); @@ -1929,7 +2507,7 @@ class RespondTakePhotoResponse final : &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 15; friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); @@ -2089,7 +2667,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 16; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -2404,7 +2982,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 17; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -2595,7 +3173,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 18; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -2786,7 +3364,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 19; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -3020,7 +3598,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 20; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -3563,6 +4141,62 @@ inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { // ------------------------------------------------------------------- +// SubscribeStartVideoStreamingRequest + +// ------------------------------------------------------------------- + +// StartVideoStreamingResponse + +// int32 stream_id = 1; +inline void StartVideoStreamingResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StartVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) + return _internal_stream_id(); +} +inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +} +inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeStopVideoStreamingRequest + +// ------------------------------------------------------------------- + +// StopVideoStreamingResponse + +// int32 stream_id = 1; +inline void StopVideoStreamingResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StopVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) + return _internal_stream_id(); +} +inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) +} +inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + // RespondTakePhotoRequest // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; diff --git a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h index f30fa82945..71b5445184 100644 --- a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h @@ -857,7 +857,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { grpc::Status StartVideoStreaming( grpc::ServerContext* /* context */, - const rpc::camera::StartVideoStreamingRequest* /* request */, + const rpc::camera::StartVideoStreamingRequest* request, rpc::camera::StartVideoStreamingResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { @@ -869,7 +869,12 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->start_video_streaming(); + if (request == nullptr) { + LogWarn() << "StartVideoStreaming sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->start_video_streaming(request->stream_id()); if (response != nullptr) { fillResponseWithResult(response, result); @@ -880,7 +885,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { grpc::Status StopVideoStreaming( grpc::ServerContext* /* context */, - const rpc::camera::StopVideoStreamingRequest* /* request */, + const rpc::camera::StopVideoStreamingRequest* request, rpc::camera::StopVideoStreamingResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { @@ -892,7 +897,12 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->stop_video_streaming(); + if (request == nullptr) { + LogWarn() << "StopVideoStreaming sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->stop_video_streaming(request->stream_id()); if (response != nullptr) { fillResponseWithResult(response, result); diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 84e1cf9144..ec1861bc7e 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -519,6 +519,88 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeStartVideoStreaming( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::StartVideoStreamingHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_start_video_streaming( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t start_video_streaming) { + rpc::camera_server::StartVideoStreamingResponse rpc_response; + + rpc_response.set_stream_id(start_video_streaming); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_start_video_streaming(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeStopVideoStreaming( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::StopVideoStreamingHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_stop_video_streaming( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t stop_video_streaming) { + rpc::camera_server::StopVideoStreamingResponse rpc_response; + + rpc_response.set_stream_id(stop_video_streaming); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_stop_video_streaming(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); diff --git a/src/mavsdk_server/test/camera_service_impl_test.cpp b/src/mavsdk_server/test/camera_service_impl_test.cpp index c439f2bf6a..34ec00508e 100644 --- a/src/mavsdk_server/test/camera_service_impl_test.cpp +++ b/src/mavsdk_server/test/camera_service_impl_test.cpp @@ -283,7 +283,7 @@ TEST_F(CameraServiceImplTest, stopVideoEvenWhenArgsAreNull) TEST_P(CameraServiceImplTest, startVideoStreamingResultIsTranslatedCorrectly) { - ON_CALL(_camera, start_video_streaming()).WillByDefault(Return(GetParam().second)); + ON_CALL(_camera, start_video_streaming(1)).WillByDefault(Return(GetParam().second)); mavsdk::rpc::camera::StartVideoStreamingResponse response; _camera_service.StartVideoStreaming(nullptr, nullptr, &response); @@ -293,14 +293,14 @@ TEST_P(CameraServiceImplTest, startVideoStreamingResultIsTranslatedCorrectly) TEST_F(CameraServiceImplTest, startsVideoStreamingEvenWhenArgsAreNull) { - EXPECT_CALL(_camera, start_video_streaming()).Times(1); + EXPECT_CALL(_camera, start_video_streaming(1)).Times(1); _camera_service.StartVideoStreaming(nullptr, nullptr, nullptr); } TEST_P(CameraServiceImplTest, stopVideoStreamingResultIsTranslatedCorrectly) { - ON_CALL(_camera, stop_video_streaming()).WillByDefault(Return(GetParam().second)); + ON_CALL(_camera, stop_video_streaming(1)).WillByDefault(Return(GetParam().second)); mavsdk::rpc::camera::StopVideoStreamingResponse response; _camera_service.StopVideoStreaming(nullptr, nullptr, &response); @@ -310,7 +310,7 @@ TEST_P(CameraServiceImplTest, stopVideoStreamingResultIsTranslatedCorrectly) TEST_F(CameraServiceImplTest, stopsVideoStreamingEvenWhenArgsAreNull) { - EXPECT_CALL(_camera, stop_video_streaming()).Times(1); + EXPECT_CALL(_camera, stop_video_streaming(1)).Times(1); _camera_service.StopVideoStreaming(nullptr, nullptr, nullptr); } From ce1bcf7f284e6bd38725e08a695580ddd7220d77 Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 17 Jun 2023 16:47:31 +0800 Subject: [PATCH 03/25] camera server: add subscribe camera mode and sample code --- examples/camera_server/camera_client.cpp | 10 +- examples/camera_server/camera_server.cpp | 4 + .../plugins/camera_server/camera_server.cpp | 24 + .../camera_server/camera_server_impl.cpp | 33 +- .../camera_server/camera_server_impl.h | 4 + .../plugins/camera_server/camera_server.h | 37 ++ .../camera_server/camera_server.grpc.pb.cc | 35 ++ .../camera_server/camera_server.grpc.pb.h | 167 ++++++- .../camera_server/camera_server.pb.cc | 459 ++++++++++++++---- .../camera_server/camera_server.pb.h | 370 +++++++++++++- .../camera_server_service_impl.h | 71 +++ 11 files changed, 1115 insertions(+), 99 deletions(-) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index e3e6588a0c..02373d1283 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -56,9 +56,17 @@ int main(int argc, const char* argv[]) void do_camera_operation(mavsdk::Camera& camera) { - auto operation_result = camera.take_photo(); + // switch to photo mode to take photo + auto operation_result = camera.set_mode(mavsdk::Camera::Mode::Photo); + std::cout << "Set camera to photo mode result : " << operation_result << std::endl; + + operation_result = camera.take_photo(); std::cout << "Take photo result : " << operation_result << std::endl; + // switch to video mode to recording video + operation_result = camera.set_mode(mavsdk::Camera::Mode::Video); + std::cout << "Set camera to video mode result : " << operation_result << std::endl; + operation_result = camera.start_video(); std::cout << "Start video result : " << operation_result << std::endl; diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index aec550bccb..82cecc06f1 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -100,4 +100,8 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) camera_server.subscribe_stop_video_streaming( [](int32_t stream_id) { std::cout << "Stop video streaming " << stream_id << std::endl; }); + + camera_server.subscribe_set_mode([](mavsdk::CameraServer::Mode mode) { + std::cout << "Set camera mode " << mode << std::endl; + }); } \ No newline at end of file diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 9c664d0713..becd22e723 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -91,6 +91,16 @@ void CameraServer::unsubscribe_stop_video_streaming(StopVideoStreamingHandle han _impl->unsubscribe_stop_video_streaming(handle); } +CameraServer::SetModeHandle CameraServer::subscribe_set_mode(const SetModeCallback& callback) +{ + return _impl->subscribe_set_mode(callback); +} + +void CameraServer::unsubscribe_set_mode(SetModeHandle handle) +{ + _impl->unsubscribe_set_mode(handle); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && @@ -236,4 +246,18 @@ operator<<(std::ostream& str, CameraServer::TakePhotoFeedback const& take_photo_ } } +std::ostream& operator<<(std::ostream& str, CameraServer::Mode const& mode) +{ + switch (mode) { + case CameraServer::Mode::Unknown: + return str << "Unknown"; + case CameraServer::Mode::Photo: + return str << "Photo"; + case CameraServer::Mode::Video: + return str << "Video"; + default: + return str << "Unknown"; + } +} + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index f624dd4926..857215df7e 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -337,6 +337,17 @@ void CameraServerImpl::unsubscribe_stop_video_streaming( return _stop_video_streaming_callbacks.unsubscribe(handle); } +CameraServer::SetModeHandle +CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback) +{ + return _set_mode_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle) +{ + _set_mode_callbacks.unsubscribe(handle); +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -645,12 +656,28 @@ CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandL { auto camera_mode = static_cast(command.params.param2); - UNUSED(camera_mode); + if (_set_mode_callbacks.empty()) { + LogDebug() << "Set mode requested with no set mode subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported set camera mode request"; + // convert camera mode enum type + CameraServer::Mode convert_camera_mode = CameraServer::Mode::Unknown; + if (camera_mode == CAMERA_MODE_IMAGE) { + convert_camera_mode = CameraServer::Mode::Photo; + } else if (camera_mode == CAMERA_MODE_VIDEO) { + convert_camera_mode = CameraServer::Mode::Video; + } + + if (convert_camera_mode == CameraServer::Mode::Unknown) { + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } + _set_mode_callbacks(convert_camera_mode); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index a9ea724c76..b2544bfc41 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -40,6 +40,9 @@ class CameraServerImpl : public ServerPluginImplBase { subscribe_stop_video_streaming(const CameraServer::StopVideoStreamingCallback& callback); void unsubscribe_stop_video_streaming(CameraServer::StopVideoStreamingHandle handle); + CameraServer::SetModeHandle subscribe_set_mode(const CameraServer::SetModeCallback& callback); + void unsubscribe_set_mode(CameraServer::SetModeHandle handle); + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -68,6 +71,7 @@ class CameraServerImpl : public ServerPluginImplBase { CallbackList _stop_video_callbacks{}; CallbackList _start_video_streaming_callbacks{}; CallbackList _stop_video_streaming_callbacks{}; + CallbackList _set_mode_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index d9a3adc8b7..b03537a10c 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -63,6 +63,22 @@ class CameraServer : public ServerPluginBase { friend std::ostream& operator<<(std::ostream& str, CameraServer::TakePhotoFeedback const& take_photo_feedback); + /** + * @brief Camera mode type. + */ + enum class Mode { + Unknown, /**< @brief Unknown mode. */ + Photo, /**< @brief Photo mode. */ + Video, /**< @brief Video mode. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::Mode`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, CameraServer::Mode const& mode); + /** * @brief Type to represent a camera information. */ @@ -348,6 +364,27 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_stop_video_streaming(StopVideoStreamingHandle handle); + /** + * @brief Callback type for subscribe_set_mode. + */ + using SetModeCallback = std::function; + + /** + * @brief Handle type for subscribe_set_mode. + */ + using SetModeHandle = Handle; + + /** + * @brief Subscribe to set camera mode requests. Each request received should response to using + * SetCameraModeResponse + */ + SetModeHandle subscribe_set_mode(const SetModeCallback& callback); + + /** + * @brief Unsubscribe from subscribe_set_mode + */ + void unsubscribe_set_mode(SetModeHandle handle); + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index b4e353f361..368fc170c8 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -32,6 +32,7 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -49,6 +50,7 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -200,6 +202,22 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingRespo return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideoStreaming_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>* CameraServerService::Stub::SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), rpcmethod_SubscribeSetMode_, context, request); +} + +void CameraServerService::Stub::async::SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeSetMode_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* CameraServerService::Stub::AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeSetMode_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* CameraServerService::Stub::PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeSetMode_, context, request, false, nullptr); +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -281,6 +299,16 @@ CameraServerService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer) { return service->SubscribeStopVideoStreaming(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[8], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::SetModeResponse>* writer) { + return service->SubscribeSetMode(ctx, req, writer); + }, this))); } CameraServerService::Service::~Service() { @@ -342,6 +370,13 @@ ::grpc::Status CameraServerService::Service::SubscribeStopVideoStreaming(::grpc: return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index afd86c192e..dfee6b6ac9 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -112,6 +112,16 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); } + // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(SubscribeSetModeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> AsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(AsyncSubscribeSetModeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -134,6 +144,8 @@ class CameraServerService final { virtual void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) = 0; // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse virtual void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) = 0; + // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + virtual void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -160,6 +172,9 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -230,6 +245,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>> SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(SubscribeSetModeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>> AsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(AsyncSubscribeSetModeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -244,6 +268,7 @@ class CameraServerService final { void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) override; void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) override; void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) override; + void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -276,6 +301,9 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; @@ -284,6 +312,7 @@ class CameraServerService final { const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideoStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeSetMode_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -307,6 +336,8 @@ class CameraServerService final { virtual ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer); // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse virtual ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer); + // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + virtual ::grpc::Status SubscribeSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -468,7 +499,27 @@ class CameraServerService final { ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodAsync(8); + } + ~WithAsyncMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -660,7 +711,29 @@ class CameraServerService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreaming( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > CallbackService; + template + class WithCallbackMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodCallback(8, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request) { return this->SubscribeSetMode(context, request); })); + } + ~WithCallbackMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetMode( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -799,6 +872,23 @@ class CameraServerService final { } }; template + class WithGenericMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodGeneric(8); + } + ~WithGenericMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -959,6 +1049,26 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodRaw(8); + } + ~WithRawMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeSetMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1135,6 +1245,28 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodRawCallback(8, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeSetMode(context, request); })); + } + ~WithRawCallbackMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeSetMode( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1351,8 +1483,35 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest,::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeSetMode() { + ::grpc::Service::MarkMethodStreamed(8, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>* streamer) { + return this->StreamedSubscribeSetMode(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeSetMode(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest,::mavsdk::rpc::camera_server::SetModeResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 836c858cd0..56b59e800f 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -231,6 +231,35 @@ struct StopVideoStreamingResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeSetModeRequest::SubscribeSetModeRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeSetModeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeSetModeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeSetModeRequestDefaultTypeInternal() {} + union { + SubscribeSetModeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeSetModeRequestDefaultTypeInternal _SubscribeSetModeRequest_default_instance_; +template +PROTOBUF_CONSTEXPR SetModeResponse::SetModeResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.mode_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct SetModeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetModeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetModeResponseDefaultTypeInternal() {} + union { + SetModeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; +template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -402,8 +431,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( @@ -532,6 +561,23 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoStreamingResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeSetModeRequest, _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::camera_server::SetModeResponse, _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::camera_server::SetModeResponse, _impl_.mode_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -645,13 +691,15 @@ static const ::_pbi::MigrationSchema { 98, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, { 107, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, { 115, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, - { 124, 134, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 136, 145, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 146, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 165, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 177, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 189, 203, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 209, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 124, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, + { 132, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, + { 141, 151, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 153, 162, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 163, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 182, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 194, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 206, 220, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 226, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -669,6 +717,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_StartVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStopVideoStreamingRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StopVideoStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeSetModeRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SetModeResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -697,72 +747,79 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "ideoStreamingRequest\"0\n\033StartVideoStream" "ingResponse\022\021\n\tstream_id\030\001 \001(\005\"$\n\"Subscr" "ibeStopVideoStreamingRequest\"/\n\032StopVide" - "oStreamingResponse\022\021\n\tstream_id\030\001 \001(\005\"\240\001" - "\n\027RespondTakePhotoRequest\022H\n\023take_photo_" - "feedback\030\001 \001(\0162+.mavsdk.rpc.camera_serve" - "r.TakePhotoFeedback\022;\n\014capture_info\030\002 \001(" - "\0132%.mavsdk.rpc.camera_server.CaptureInfo" - "\"f\n\030RespondTakePhotoResponse\022J\n\024camera_s" - "erver_result\030\001 \001(\0132,.mavsdk.rpc.camera_s" - "erver.CameraServerResult\"\276\002\n\013Information" - "\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(" - "\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal_len" - "gth_mm\030\004 \001(\002\022!\n\031horizontal_sensor_size_m" - "m\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006 \001(\002" - "\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036\n\026ve" - "rtical_resolution_px\030\010 \001(\r\022\017\n\007lens_id\030\t " - "\001(\r\022\037\n\027definition_file_version\030\n \001(\r\022\033\n\023" - "definition_file_uri\030\013 \001(\t\"q\n\010Position\022\024\n" - "\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001" - "(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023relat" - "ive_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030" - "\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320" - "\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".mavsd" - "k.rpc.camera_server.Position\022A\n\023attitude" - "_quaternion\030\002 \001(\0132$.mavsdk.rpc.camera_se" - "rver.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\n" - "is_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_" - "url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006resu" - "lt\030\001 \001(\01623.mavsdk.rpc.camera_server.Came" - "raServerResult.Result\022\022\n\nresult_str\030\002 \001(" - "\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESU" - "LT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013" - "RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESU" - "LT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT" - "_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010*" - "\216\001\n\021TakePhotoFeedback\022\037\n\033TAKE_PHOTO_FEED" - "BACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK" - "\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE" - "_PHOTO_FEEDBACK_FAILED\020\0032\310\010\n\023CameraServe" - "rService\022y\n\016SetInformation\022/.mavsdk.rpc." - "camera_server.SetInformationRequest\0320.ma" - "vsdk.rpc.camera_server.SetInformationRes" - "ponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rp" - "c.camera_server.SetInProgressRequest\032/.m" - "avsdk.rpc.camera_server.SetInProgressRes" - "ponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavs" - "dk.rpc.camera_server.SubscribeTakePhotoR" - "equest\032+.mavsdk.rpc.camera_server.TakePh" - "otoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\022" - "1.mavsdk.rpc.camera_server.RespondTakePh" - "otoRequest\0322.mavsdk.rpc.camera_server.Re" - "spondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023Subscri" - "beStartVideo\0224.mavsdk.rpc.camera_server." - "SubscribeStartVideoRequest\032,.mavsdk.rpc." - "camera_server.StartVideoResponse\"\004\200\265\030\0000\001" - "\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.came" - "ra_server.SubscribeStopVideoRequest\032+.ma" - "vsdk.rpc.camera_server.StopVideoResponse" - "\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideoStreamin" - "g\022=.mavsdk.rpc.camera_server.SubscribeSt" - "artVideoStreamingRequest\0325.mavsdk.rpc.ca" - "mera_server.StartVideoStreamingResponse\"" - "\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoStreaming\022" - "<.mavsdk.rpc.camera_server.SubscribeStop" - "VideoStreamingRequest\0324.mavsdk.rpc.camer" - "a_server.StopVideoStreamingResponse\"\004\200\265\030" - "\0000\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" - "rverProtob\006proto3" + "oStreamingResponse\022\021\n\tstream_id\030\001 \001(\005\"\031\n" + "\027SubscribeSetModeRequest\"\?\n\017SetModeRespo" + "nse\022,\n\004mode\030\001 \001(\0162\036.mavsdk.rpc.camera_se" + "rver.Mode\"\240\001\n\027RespondTakePhotoRequest\022H\n" + "\023take_photo_feedback\030\001 \001(\0162+.mavsdk.rpc." + "camera_server.TakePhotoFeedback\022;\n\014captu" + "re_info\030\002 \001(\0132%.mavsdk.rpc.camera_server" + ".CaptureInfo\"f\n\030RespondTakePhotoResponse" + "\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk." + "rpc.camera_server.CameraServerResult\"\276\002\n" + "\013Information\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmod" + "el_name\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022" + "\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031horizontal_s" + "ensor_size_mm\030\005 \001(\002\022\037\n\027vertical_sensor_s" + "ize_mm\030\006 \001(\002\022 \n\030horizontal_resolution_px" + "\030\007 \001(\r\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017" + "\n\007lens_id\030\t \001(\r\022\037\n\027definition_file_versi" + "on\030\n \001(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n" + "\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongi" + "tude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 " + "\001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\nQuat" + "ernion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022" + "\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001" + " \001(\0132\".mavsdk.rpc.camera_server.Position" + "\022A\n\023attitude_quaternion\030\002 \001(\0132$.mavsdk.r" + "pc.camera_server.Quaternion\022\023\n\013time_utc_" + "us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 " + "\001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerRe" + "sult\022C\n\006result\030\001 \001(\01623.mavsdk.rpc.camera" + "_server.CameraServerResult.Result\022\022\n\nres" + "ult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNO" + "WN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PR" + "OGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENI" + "ED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT" + "\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_" + "NO_SYSTEM\020\010*\216\001\n\021TakePhotoFeedback\022\037\n\033TAK" + "E_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO" + "_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BU" + "SY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_FAILED\020\003*8\n\004" + "Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016" + "\n\nMODE_VIDEO\020\0022\302\t\n\023CameraServerService\022y" + "\n\016SetInformation\022/.mavsdk.rpc.camera_ser" + "ver.SetInformationRequest\0320.mavsdk.rpc.c" + "amera_server.SetInformationResponse\"\004\200\265\030" + "\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_s" + "erver.SetInProgressRequest\032/.mavsdk.rpc." + "camera_server.SetInProgressResponse\"\004\200\265\030" + "\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.cam" + "era_server.SubscribeTakePhotoRequest\032+.m" + "avsdk.rpc.camera_server.TakePhotoRespons" + "e\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.r" + "pc.camera_server.RespondTakePhotoRequest" + "\0322.mavsdk.rpc.camera_server.RespondTakeP" + "hotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVid" + "eo\0224.mavsdk.rpc.camera_server.SubscribeS" + "tartVideoRequest\032,.mavsdk.rpc.camera_ser" + "ver.StartVideoResponse\"\004\200\265\030\0000\001\022~\n\022Subscr" + "ibeStopVideo\0223.mavsdk.rpc.camera_server." + "SubscribeStopVideoRequest\032+.mavsdk.rpc.c" + "amera_server.StopVideoResponse\"\004\200\265\030\0000\001\022\234" + "\001\n\034SubscribeStartVideoStreaming\022=.mavsdk" + ".rpc.camera_server.SubscribeStartVideoSt" + "reamingRequest\0325.mavsdk.rpc.camera_serve" + "r.StartVideoStreamingResponse\"\004\200\265\030\0000\001\022\231\001" + "\n\033SubscribeStopVideoStreaming\022<.mavsdk.r" + "pc.camera_server.SubscribeStopVideoStrea" + "mingRequest\0324.mavsdk.rpc.camera_server.S" + "topVideoStreamingResponse\"\004\200\265\030\0000\001\022x\n\020Sub" + "scribeSetMode\0221.mavsdk.rpc.camera_server" + ".SubscribeSetModeRequest\032).mavsdk.rpc.ca" + "mera_server.SetModeResponse\"\004\200\265\030\0000\001B,\n\027i" + "o.mavsdk.camera_serverB\021CameraServerProt" + "ob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -772,13 +829,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 3377, + 3649, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 21, + 23, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -860,6 +917,20 @@ bool TakePhotoFeedback_IsValid(int value) { return false; } } +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Mode_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; +} +bool Mode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} // =================================================================== class SetInformationRequest::_Internal { @@ -2710,6 +2781,218 @@ ::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingResponse::GetMetadata() cons } // =================================================================== +class SubscribeSetModeRequest::_Internal { + public: +}; + +SubscribeSetModeRequest::SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) +} +SubscribeSetModeRequest::SubscribeSetModeRequest(const SubscribeSetModeRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeSetModeRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeSetModeRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeSetModeRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeSetModeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); +} +// =================================================================== + +class SetModeResponse::_Internal { + public: +}; + +SetModeResponse::SetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetModeResponse) +} +SetModeResponse::SetModeResponse(const SetModeResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetModeResponse) +} + +inline void SetModeResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.mode_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +SetModeResponse::~SetModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetModeResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetModeResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SetModeResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetModeResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.mode_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.Mode mode = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_mode(static_cast<::mavsdk::rpc::camera_server::Mode>(val)); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetModeResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetModeResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Mode mode = 1; + if (this->_internal_mode() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_mode(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.SetModeResponse) + return target; +} + +::size_t SetModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetModeResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Mode mode = 1; + if (this->_internal_mode() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetModeResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetModeResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetModeResponse::GetClassData() const { return &_class_data_; } + + +void SetModeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.SetModeResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_mode() != 0) { + _this->_internal_set_mode(from._internal_mode()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetModeResponse::CopyFrom(const SetModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetModeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetModeResponse::IsInitialized() const { + return true; +} + +void SetModeResponse::InternalSwap(SetModeResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.mode_, other->_impl_.mode_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetModeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); +} +// =================================================================== + class RespondTakePhotoRequest::_Internal { public: using HasBits = decltype(std::declval()._impl_._has_bits_); @@ -2948,7 +3231,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); } // =================================================================== @@ -3153,7 +3436,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); } // =================================================================== @@ -3738,7 +4021,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); } // =================================================================== @@ -4043,7 +4326,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); } // =================================================================== @@ -4348,7 +4631,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); } // =================================================================== @@ -4751,7 +5034,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); } // =================================================================== @@ -4980,7 +5263,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -5043,6 +5326,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoStreamingRes Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetModeResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetModeResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetModeResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 914e39d7f1..be42de2c4a 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -89,6 +89,9 @@ extern SetInformationRequestDefaultTypeInternal _SetInformationRequest_default_i class SetInformationResponse; struct SetInformationResponseDefaultTypeInternal; extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; +class SetModeResponse; +struct SetModeResponseDefaultTypeInternal; +extern SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; class StartVideoResponse; struct StartVideoResponseDefaultTypeInternal; extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; @@ -101,6 +104,9 @@ extern StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_ class StopVideoStreamingResponse; struct StopVideoStreamingResponseDefaultTypeInternal; extern StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; +class SubscribeSetModeRequest; +struct SubscribeSetModeRequestDefaultTypeInternal; +extern SubscribeSetModeRequestDefaultTypeInternal _SubscribeSetModeRequest_default_instance_; class SubscribeStartVideoRequest; struct SubscribeStartVideoRequestDefaultTypeInternal; extern SubscribeStartVideoRequestDefaultTypeInternal _SubscribeStartVideoRequest_default_instance_; @@ -146,6 +152,8 @@ ::mavsdk::rpc::camera_server::SetInformationRequest* Arena::CreateMaybeMessage<: template <> ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetInformationResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::SetModeResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetModeResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoResponse>(Arena*); template <> ::mavsdk::rpc::camera_server::StartVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoStreamingResponse>(Arena*); @@ -154,6 +162,8 @@ ::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage<::mav template <> ::mavsdk::rpc::camera_server::StopVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoStreamingResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::SubscribeSetModeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeSetModeRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest>(Arena*); @@ -243,6 +253,39 @@ inline bool TakePhotoFeedback_Parse(absl::string_view name, TakePhotoFeedback* v return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( TakePhotoFeedback_descriptor(), name, value); } +enum Mode : int { + MODE_UNKNOWN = 0, + MODE_PHOTO = 1, + MODE_VIDEO = 2, + Mode_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + Mode_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool Mode_IsValid(int value); +constexpr Mode Mode_MIN = static_cast(0); +constexpr Mode Mode_MAX = static_cast(2); +constexpr int Mode_ARRAYSIZE = 2 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +Mode_descriptor(); +template +const std::string& Mode_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to Mode_Name()."); + return Mode_Name(static_cast(value)); +} +template <> +inline const std::string& Mode_Name(Mode value) { + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool Mode_Parse(absl::string_view name, Mode* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + Mode_descriptor(), name, value); +} // =================================================================== @@ -2279,6 +2322,285 @@ class StopVideoStreamingResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- +class SubscribeSetModeRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeSetModeRequest) */ { + public: + inline SubscribeSetModeRequest() : SubscribeSetModeRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeSetModeRequest(const SubscribeSetModeRequest& from); + SubscribeSetModeRequest(SubscribeSetModeRequest&& from) noexcept + : SubscribeSetModeRequest() { + *this = ::std::move(from); + } + + inline SubscribeSetModeRequest& operator=(const SubscribeSetModeRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeSetModeRequest& operator=(SubscribeSetModeRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeSetModeRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeSetModeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeSetModeRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 14; + + friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeSetModeRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeSetModeRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeSetModeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeSetModeRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeSetModeRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeSetModeRequest"; + } + protected: + explicit SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeSetModeRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SetModeResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetModeResponse) */ { + public: + inline SetModeResponse() : SetModeResponse(nullptr) {} + ~SetModeResponse() override; + template + explicit PROTOBUF_CONSTEXPR SetModeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetModeResponse(const SetModeResponse& from); + SetModeResponse(SetModeResponse&& from) noexcept + : SetModeResponse() { + *this = ::std::move(from); + } + + inline SetModeResponse& operator=(const SetModeResponse& from) { + CopyFrom(from); + return *this; + } + inline SetModeResponse& operator=(SetModeResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SetModeResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetModeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetModeResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 15; + + friend void swap(SetModeResponse& a, SetModeResponse& b) { + a.Swap(&b); + } + inline void Swap(SetModeResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetModeResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetModeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetModeResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const SetModeResponse& from) { + SetModeResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetModeResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SetModeResponse"; + } + protected: + explicit SetModeResponse(::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 { + kModeFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.Mode mode = 1; + void clear_mode() ; + ::mavsdk::rpc::camera_server::Mode mode() const; + void set_mode(::mavsdk::rpc::camera_server::Mode value); + + private: + ::mavsdk::rpc::camera_server::Mode _internal_mode() const; + void _internal_set_mode(::mavsdk::rpc::camera_server::Mode value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetModeResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + int mode_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RespondTakePhotoRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: @@ -2335,7 +2657,7 @@ class RespondTakePhotoRequest final : &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 16; friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); @@ -2507,7 +2829,7 @@ class RespondTakePhotoResponse final : &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 17; friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); @@ -2667,7 +2989,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 18; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -2982,7 +3304,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 19; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -3173,7 +3495,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 20; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -3364,7 +3686,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 21; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -3598,7 +3920,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 22; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -4197,6 +4519,34 @@ inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) // ------------------------------------------------------------------- +// SubscribeSetModeRequest + +// ------------------------------------------------------------------- + +// SetModeResponse + +// .mavsdk.rpc.camera_server.Mode mode = 1; +inline void SetModeResponse::clear_mode() { + _impl_.mode_ = 0; +} +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::mode() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetModeResponse.mode) + return _internal_mode(); +} +inline void SetModeResponse::set_mode(::mavsdk::rpc::camera_server::Mode value) { + _internal_set_mode(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetModeResponse.mode) +} +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::_internal_mode() const { + return static_cast<::mavsdk::rpc::camera_server::Mode>(_impl_.mode_); +} +inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mode value) { + ; + _impl_.mode_ = value; +} + +// ------------------------------------------------------------------- + // RespondTakePhotoRequest // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; @@ -5277,6 +5627,12 @@ template <> inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::TakePhotoFeedback>() { return ::mavsdk::rpc::camera_server::TakePhotoFeedback_descriptor(); } +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::Mode> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::Mode>() { + return ::mavsdk::rpc::camera_server::Mode_descriptor(); +} PROTOBUF_NAMESPACE_CLOSE diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index ec1861bc7e..05ffceaf43 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -82,6 +82,36 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } } + static rpc::camera_server::Mode translateToRpcMode(const mavsdk::CameraServer::Mode& mode) + { + switch (mode) { + default: + LogErr() << "Unknown mode enum value: " << static_cast(mode); + // FALLTHROUGH + case mavsdk::CameraServer::Mode::Unknown: + return rpc::camera_server::MODE_UNKNOWN; + case mavsdk::CameraServer::Mode::Photo: + return rpc::camera_server::MODE_PHOTO; + case mavsdk::CameraServer::Mode::Video: + return rpc::camera_server::MODE_VIDEO; + } + } + + static mavsdk::CameraServer::Mode translateFromRpcMode(const rpc::camera_server::Mode mode) + { + switch (mode) { + default: + LogErr() << "Unknown mode enum value: " << static_cast(mode); + // FALLTHROUGH + case rpc::camera_server::MODE_UNKNOWN: + return mavsdk::CameraServer::Mode::Unknown; + case rpc::camera_server::MODE_PHOTO: + return mavsdk::CameraServer::Mode::Photo; + case rpc::camera_server::MODE_VIDEO: + return mavsdk::CameraServer::Mode::Video; + } + } + static std::unique_ptr translateToRpcInformation(const mavsdk::CameraServer::Information& information) { @@ -601,6 +631,47 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeSetMode( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeSetModeRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::SetModeHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_set_mode( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::CameraServer::Mode set_mode) { + rpc::camera_server::SetModeResponse rpc_response; + + rpc_response.set_mode(translateToRpcMode(set_mode)); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_set_mode(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); From cabd727901c273bba433f392175ee06d03b4388a Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 17 Jun 2023 17:33:29 +0800 Subject: [PATCH 04/25] camera server: add storage information and capture stauts subscribe --- examples/camera_server/camera_client.cpp | 9 + examples/camera_server/camera_server.cpp | 62 +- src/mavsdk/plugins/camera/camera_impl.cpp | 15 + .../plugins/camera_server/camera_server.cpp | 162 + .../camera_server/camera_server_impl.cpp | 181 +- .../camera_server/camera_server_impl.h | 14 + .../plugins/camera_server/camera_server.h | 194 + .../camera_server/camera_server.grpc.pb.cc | 154 + .../camera_server/camera_server.grpc.pb.h | 648 ++- .../camera_server/camera_server.pb.cc | 5090 ++++++++++++----- .../camera_server/camera_server.pb.h | 3896 +++++++++++-- .../camera_server_service_impl.h | 386 ++ 12 files changed, 8891 insertions(+), 1920 deletions(-) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 02373d1283..5fc54bd624 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -49,8 +49,17 @@ int main(int argc, const char* argv[]) std::cout << info << std::endl; }); + camera.subscribe_status([](mavsdk::Camera::Status status) { + std::cout << "Camera status:" << std::endl; + std::cout << status << std::endl; + }); + do_camera_operation(camera); + // for test subscribe camera status, so don't end the process + while (true) { + std::this_thread::sleep_for(std::chrono::seconds(1)); + } return 0; } diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 82cecc06f1..8e89554bb3 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -1,5 +1,7 @@ #include #include +#include +#include #include #include @@ -55,11 +57,19 @@ int main(int argc, char** argv) return 0; } +// sample for camera current status +std::chrono::steady_clock::time_point start_video_time; +bool is_recording_video = false; +bool is_capture_in_progress = false; +int32_t image_count = 0; + static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) { camera_server.subscribe_take_photo([&camera_server](int32_t index) { camera_server.set_in_progress(true); + is_capture_in_progress = true; + std::cout << "taking a picture (" << +index << ")..." << std::endl; // TODO : actually capture image here @@ -74,7 +84,7 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) std::chrono::system_clock::now().time_since_epoch()) .count(); auto success = true; - + image_count++; camera_server.set_in_progress(false); camera_server.respond_take_photo( @@ -87,13 +97,20 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) .index = index, .file_url = {}, }); + + is_capture_in_progress = false; }); - camera_server.subscribe_start_video( - [](int32_t stream_id) { std::cout << "Start video record" << std::endl; }); + camera_server.subscribe_start_video([](int32_t stream_id) { + std::cout << "Start video record" << std::endl; + is_recording_video = true; + start_video_time = std::chrono::steady_clock::now(); + }); - camera_server.subscribe_stop_video( - [](int32_t stream_id) { std::cout << "Stop video record" << std::endl; }); + camera_server.subscribe_stop_video([](int32_t stream_id) { + std::cout << "Stop video record" << std::endl; + is_recording_video = false; + }); camera_server.subscribe_start_video_streaming( [](int32_t stream_id) { std::cout << "Start video streaming " << stream_id << std::endl; }); @@ -104,4 +121,39 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) camera_server.subscribe_set_mode([](mavsdk::CameraServer::Mode mode) { std::cout << "Set camera mode " << mode << std::endl; }); + + camera_server.subscribe_storage_information([&camera_server](int32_t storage_id) { + mavsdk::CameraServer::StorageInformation storage_information; + constexpr int kTotalStorage = 4 * 1024 * 1024; + storage_information.total_storage_mib = kTotalStorage; + storage_information.used_storage_mib = 100; + storage_information.available_storage_mib = + kTotalStorage - storage_information.used_storage_mib; + storage_information.storage_status = + mavsdk::CameraServer::StorageInformation::StorageStatus::Formatted; + storage_information.storage_type = + mavsdk::CameraServer::StorageInformation::StorageType::Microsd; + + camera_server.respond_storage_information(storage_information); + }); + + camera_server.subscribe_capture_status([&camera_server](int32_t reserved) { + mavsdk::CameraServer::CaptureStatus capture_status; + capture_status.image_count = image_count; + capture_status.image_status = + is_capture_in_progress ? + mavsdk::CameraServer::CaptureStatus::ImageStatus::CaptureInProgress : + mavsdk::CameraServer::CaptureStatus::ImageStatus::Idle; + capture_status.video_status = + is_recording_video ? + mavsdk::CameraServer::CaptureStatus::VideoStatus::CaptureInProgress : + mavsdk::CameraServer::CaptureStatus::VideoStatus::Idle; + auto current_time = std::chrono::steady_clock::now(); + if (is_recording_video) { + capture_status.recording_time_s = + std::chrono::duration_cast(current_time - start_video_time) + .count(); + } + camera_server.respond_capture_status(capture_status); + }); } \ No newline at end of file diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index d3ce513875..f86d836465 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -598,6 +598,21 @@ CameraImpl::subscribe_information(const Camera::InformationCallback& callback) std::lock_guard lock(_information.mutex); auto handle = _information.subscription_callbacks.subscribe(callback); + // If there was already a subscription, cancel the call + if (_status.call_every_cookie) { + _system_impl->remove_call_every(_status.call_every_cookie); + } + + if (callback) { + if (_status.call_every_cookie == nullptr) { + _system_impl->add_call_every( + [this]() { request_status(); }, 1.0, &_status.call_every_cookie); + } + } else { + _system_impl->remove_call_every(_status.call_every_cookie); + _status.call_every_cookie = nullptr; + } + return handle; } diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index becd22e723..30d1cc7838 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -15,6 +15,9 @@ using Position = CameraServer::Position; using Quaternion = CameraServer::Quaternion; using CaptureInfo = CameraServer::CaptureInfo; +using StorageInformation = CameraServer::StorageInformation; +using CaptureStatus = CameraServer::CaptureStatus; + CameraServer::CameraServer(std::shared_ptr server_component) : ServerPluginBase(), _impl{std::make_unique(server_component)} @@ -101,6 +104,39 @@ void CameraServer::unsubscribe_set_mode(SetModeHandle handle) _impl->unsubscribe_set_mode(handle); } +CameraServer::StorageInformationHandle +CameraServer::subscribe_storage_information(const StorageInformationCallback& callback) +{ + return _impl->subscribe_storage_information(callback); +} + +void CameraServer::unsubscribe_storage_information(StorageInformationHandle handle) +{ + _impl->unsubscribe_storage_information(handle); +} + +CameraServer::Result +CameraServer::respond_storage_information(StorageInformation storage_information) const +{ + return _impl->respond_storage_information(storage_information); +} + +CameraServer::CaptureStatusHandle +CameraServer::subscribe_capture_status(const CaptureStatusCallback& callback) +{ + return _impl->subscribe_capture_status(callback); +} + +void CameraServer::unsubscribe_capture_status(CaptureStatusHandle handle) +{ + _impl->unsubscribe_capture_status(handle); +} + +CameraServer::Result CameraServer::respond_capture_status(CaptureStatus capture_status) const +{ + return _impl->respond_capture_status(capture_status); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && @@ -229,6 +265,132 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result) } } +std::ostream& +operator<<(std::ostream& str, CameraServer::StorageInformation::StorageStatus const& storage_status) +{ + switch (storage_status) { + case CameraServer::StorageInformation::StorageStatus::NotAvailable: + return str << "Not Available"; + case CameraServer::StorageInformation::StorageStatus::Unformatted: + return str << "Unformatted"; + case CameraServer::StorageInformation::StorageStatus::Formatted: + return str << "Formatted"; + case CameraServer::StorageInformation::StorageStatus::NotSupported: + return str << "Not Supported"; + default: + return str << "Unknown"; + } +} + +std::ostream& +operator<<(std::ostream& str, CameraServer::StorageInformation::StorageType const& storage_type) +{ + switch (storage_type) { + case CameraServer::StorageInformation::StorageType::Unknown: + return str << "Unknown"; + case CameraServer::StorageInformation::StorageType::UsbStick: + return str << "Usb Stick"; + case CameraServer::StorageInformation::StorageType::Sd: + return str << "Sd"; + case CameraServer::StorageInformation::StorageType::Microsd: + return str << "Microsd"; + case CameraServer::StorageInformation::StorageType::Hd: + return str << "Hd"; + case CameraServer::StorageInformation::StorageType::Other: + return str << "Other"; + default: + return str << "Unknown"; + } +} +bool operator==( + const CameraServer::StorageInformation& lhs, const CameraServer::StorageInformation& rhs) +{ + return ((std::isnan(rhs.used_storage_mib) && std::isnan(lhs.used_storage_mib)) || + rhs.used_storage_mib == lhs.used_storage_mib) && + ((std::isnan(rhs.available_storage_mib) && std::isnan(lhs.available_storage_mib)) || + rhs.available_storage_mib == lhs.available_storage_mib) && + ((std::isnan(rhs.total_storage_mib) && std::isnan(lhs.total_storage_mib)) || + rhs.total_storage_mib == lhs.total_storage_mib) && + (rhs.storage_status == lhs.storage_status) && (rhs.storage_id == lhs.storage_id) && + (rhs.storage_type == lhs.storage_type) && + ((std::isnan(rhs.read_speed) && std::isnan(lhs.read_speed)) || + rhs.read_speed == lhs.read_speed) && + ((std::isnan(rhs.write_speed) && std::isnan(lhs.write_speed)) || + rhs.write_speed == lhs.write_speed); +} + +std::ostream& +operator<<(std::ostream& str, CameraServer::StorageInformation const& storage_information) +{ + str << std::setprecision(15); + str << "storage_information:" << '\n' << "{\n"; + str << " used_storage_mib: " << storage_information.used_storage_mib << '\n'; + str << " available_storage_mib: " << storage_information.available_storage_mib << '\n'; + str << " total_storage_mib: " << storage_information.total_storage_mib << '\n'; + str << " storage_status: " << storage_information.storage_status << '\n'; + str << " storage_id: " << storage_information.storage_id << '\n'; + str << " storage_type: " << storage_information.storage_type << '\n'; + str << " read_speed: " << storage_information.read_speed << '\n'; + str << " write_speed: " << storage_information.write_speed << '\n'; + str << '}'; + return str; +} + +std::ostream& +operator<<(std::ostream& str, CameraServer::CaptureStatus::ImageStatus const& image_status) +{ + switch (image_status) { + case CameraServer::CaptureStatus::ImageStatus::Idle: + return str << "Idle"; + case CameraServer::CaptureStatus::ImageStatus::CaptureInProgress: + return str << "Capture In Progress"; + case CameraServer::CaptureStatus::ImageStatus::IntervalIdle: + return str << "Interval Idle"; + case CameraServer::CaptureStatus::ImageStatus::IntervalInProgress: + return str << "Interval In Progress"; + default: + return str << "Unknown"; + } +} + +std::ostream& +operator<<(std::ostream& str, CameraServer::CaptureStatus::VideoStatus const& video_status) +{ + switch (video_status) { + case CameraServer::CaptureStatus::VideoStatus::Idle: + return str << "Idle"; + case CameraServer::CaptureStatus::VideoStatus::CaptureInProgress: + return str << "Capture In Progress"; + default: + return str << "Unknown"; + } +} +bool operator==(const CameraServer::CaptureStatus& lhs, const CameraServer::CaptureStatus& rhs) +{ + return ((std::isnan(rhs.image_interval) && std::isnan(lhs.image_interval)) || + rhs.image_interval == lhs.image_interval) && + ((std::isnan(rhs.recording_time_s) && std::isnan(lhs.recording_time_s)) || + rhs.recording_time_s == lhs.recording_time_s) && + ((std::isnan(rhs.available_capacity) && std::isnan(lhs.available_capacity)) || + rhs.available_capacity == lhs.available_capacity) && + (rhs.image_status == lhs.image_status) && (rhs.video_status == lhs.video_status) && + (rhs.image_count == lhs.image_count); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::CaptureStatus const& capture_status) +{ + str << std::setprecision(15); + str << "capture_status:" << '\n' << "{\n"; + str << " image_interval: " << capture_status.image_interval << '\n'; + str << " recording_time_s: " << capture_status.recording_time_s << '\n'; + str << " available_capacity: " << capture_status.available_capacity << '\n'; + str << " image_status: " << capture_status.image_status << '\n'; + str << " video_status: " << capture_status.video_status << '\n'; + str << " image_count: " << capture_status.image_count << '\n'; + str << '}'; + return str; +} + std::ostream& operator<<(std::ostream& str, CameraServer::TakePhotoFeedback const& take_photo_feedback) { diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 857215df7e..2baba09bc3 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -348,6 +348,156 @@ void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle) _set_mode_callbacks.unsubscribe(handle); } +CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information( + const CameraServer::StorageInformationCallback& callback) +{ + return _storage_information_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_storage_information( + CameraServer::StorageInformationHandle handle) +{ + _storage_information_callbacks.unsubscribe(handle); +} + +CameraServer::Result CameraServerImpl::respond_storage_information( + CameraServer::StorageInformation storage_information) const +{ + const uint8_t storage_count = 1; + + const float total_capacity = storage_information.total_storage_mib; + const float used_capacity = storage_information.used_storage_mib; + const float available_capacity = storage_information.available_storage_mib; + const float read_speed = storage_information.read_speed; + const float write_speed = storage_information.write_speed; + + auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED; + switch (storage_information.storage_status) { + case CameraServer::StorageInformation::StorageStatus::NotAvailable: + status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED; + break; + case CameraServer::StorageInformation::StorageStatus::Unformatted: + status = STORAGE_STATUS::STORAGE_STATUS_UNFORMATTED; + break; + case CameraServer::StorageInformation::StorageStatus::Formatted: + status = STORAGE_STATUS::STORAGE_STATUS_READY; + break; + case CameraServer::StorageInformation::StorageStatus::NotSupported: + status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED; + break; + } + + auto type = STORAGE_TYPE::STORAGE_TYPE_UNKNOWN; + switch (storage_information.storage_type) { + case CameraServer::StorageInformation::StorageType::UsbStick: + type = STORAGE_TYPE::STORAGE_TYPE_USB_STICK; + break; + case CameraServer::StorageInformation::StorageType::Sd: + type = STORAGE_TYPE::STORAGE_TYPE_SD; + break; + case CameraServer::StorageInformation::StorageType::Microsd: + type = STORAGE_TYPE::STORAGE_TYPE_MICROSD; + break; + case CameraServer::StorageInformation::StorageType::Hd: + type = STORAGE_TYPE::STORAGE_TYPE_HD; + break; + case CameraServer::StorageInformation::StorageType::Other: + type = STORAGE_TYPE::STORAGE_TYPE_OTHER; + break; + default: + break; + } + + std::string name(""); + // This needs to be long enough, otherwise the memcpy in mavlink overflows. + name.resize(32); + const uint8_t storage_usage = 0; + + _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message{}; + mavlink_msg_storage_information_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + static_cast(_server_component_impl->get_time().elapsed_s() * 1e3), + _last_storage_id, + storage_count, + status, + total_capacity, + used_capacity, + available_capacity, + read_speed, + write_speed, + type, + name.data(), + storage_usage); + return message; + }); + + return CameraServer::Result::Success; +} + +CameraServer::CaptureStatusHandle +CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback) +{ + return _capture_status_callbacks.subscribe(callback); +} +void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle) +{ + _capture_status_callbacks.unsubscribe(handle); +} + +CameraServer::Result +CameraServerImpl::respond_capture_status(CameraServer::CaptureStatus capture_status) const +{ + uint8_t image_status{}; + if (capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::CaptureInProgress || + capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) { + image_status |= StatusFlags::IN_PROGRESS; + } + + if (capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle || + capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::IntervalInProgress || + _is_image_capture_interval_set) { + image_status |= StatusFlags::INTERVAL_SET; + } + + uint8_t video_status = 0; + if (capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) { + video_status = 0; + } else if ( + capture_status.video_status == + CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) { + video_status = 1; + } + const uint32_t recording_time_ms = + static_cast(static_cast(capture_status.recording_time_s) * 1e3); + const float available_capacity = capture_status.available_capacity; + + _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message{}; + mavlink_msg_camera_capture_status_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + static_cast(_server_component_impl->get_time().elapsed_s() * 1e3), + image_status, + video_status, + _image_capture_timer_interval_s, + recording_time_ms, + available_capacity, + _image_capture_count); + return message; + }); + + return CameraServer::Result::Success; +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -471,9 +621,9 @@ std::optional CameraServerImpl::process_camera_settings_r } // ack needs to be sent before camera information message - auto ack_msg = + auto command_ack = _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); - _server_component_impl->send_command_ack(ack_msg); + _server_component_impl->send_command_ack(command_ack); LogDebug() << "sent settings ack"; // FIXME: why is this needed to prevent dropping messages? @@ -515,14 +665,21 @@ std::optional CameraServerImpl::process_storage_informati command, MAV_RESULT::MAV_RESULT_ACCEPTED); } - // ack needs to be sent before camera information message + if (_storage_information_callbacks.empty()) { + LogDebug() + << "Get storage information requested with no set storage information subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } + + // ack needs to be sent before storage information message auto command_ack = _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - LogDebug() << "sent storage ack"; - // FIXME: why is this needed to prevent dropping messages? - std::this_thread::sleep_for(std::chrono::milliseconds(100)); + // TODO may need support multi storage id + _last_storage_id = storage_id; + _storage_information_callbacks(storage_id); // unsupported const uint8_t storage_count = 0; @@ -594,13 +751,19 @@ std::optional CameraServerImpl::process_camera_capture_st command, MAV_RESULT::MAV_RESULT_ACCEPTED); } - // ack needs to be sent before camera information message + if (_capture_status_callbacks.empty()) { + LogDebug() << "process camera capture status requested with no capture status subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } + + // ack needs to be sent before camera capture status message auto command_ack = _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - // FIXME: why is this needed to prevent dropping messages? - std::this_thread::sleep_for(std::chrono::milliseconds(100)); + // may not need param for now ,just use zero + _capture_status_callbacks(0); uint8_t image_status{}; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index b2544bfc41..34dcb11d20 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -43,6 +43,17 @@ class CameraServerImpl : public ServerPluginImplBase { CameraServer::SetModeHandle subscribe_set_mode(const CameraServer::SetModeCallback& callback); void unsubscribe_set_mode(CameraServer::SetModeHandle handle); + CameraServer::StorageInformationHandle + subscribe_storage_information(const CameraServer::StorageInformationCallback& callback); + void unsubscribe_storage_information(CameraServer::StorageInformationHandle handle); + CameraServer::Result + respond_storage_information(CameraServer::StorageInformation storage_information) const; + + CameraServer::CaptureStatusHandle + subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback); + void unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle); + CameraServer::Result respond_capture_status(CameraServer::CaptureStatus capture_status) const; + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -72,8 +83,11 @@ class CameraServerImpl : public ServerPluginImplBase { CallbackList _start_video_streaming_callbacks{}; CallbackList _stop_video_streaming_callbacks{}; CallbackList _set_mode_callbacks{}; + CallbackList _storage_information_callbacks{}; + CallbackList _capture_status_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; + uint8_t _last_storage_id; bool parse_version_string(const std::string& version_str); bool parse_version_string(const std::string& version_str, uint32_t& version); diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index b03537a10c..e1b3356bf0 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -222,6 +222,139 @@ class CameraServer : public ServerPluginBase { */ friend std::ostream& operator<<(std::ostream& str, CameraServer::Result const& result); + /** + * @brief Information about the camera storage. + */ + struct StorageInformation { + /** + * @brief Storage status type. + */ + enum class StorageStatus { + NotAvailable, /**< @brief Storage not available. */ + Unformatted, /**< @brief Storage is not formatted (i.e. has no recognized file system). + */ + Formatted, /**< @brief Storage is formatted (i.e. has recognized a file system). */ + NotSupported, /**< @brief Storage status is not supported. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::StorageStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, + CameraServer::StorageInformation::StorageStatus const& storage_status); + + /** + * @brief Storage type. + */ + enum class StorageType { + Unknown, /**< @brief Storage type unknown. */ + UsbStick, /**< @brief Storage type USB stick. */ + Sd, /**< @brief Storage type SD card. */ + Microsd, /**< @brief Storage type MicroSD card. */ + Hd, /**< @brief Storage type HD mass storage. */ + Other, /**< @brief Storage type other, not listed. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::StorageType`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<( + std::ostream& str, CameraServer::StorageInformation::StorageType const& storage_type); + + float used_storage_mib{}; /**< @brief Used storage (in MiB) */ + float available_storage_mib{}; /**< @brief Available storage (in MiB) */ + float total_storage_mib{}; /**< @brief Total storage (in MiB) */ + StorageStatus storage_status{}; /**< @brief Storage status */ + uint32_t storage_id{}; /**< @brief Storage ID starting at 1 */ + StorageType storage_type{}; /**< @brief Storage type */ + float read_speed{}; /**< @brief Read speed [MiB/s] */ + float write_speed{}; /**< @brief Write speed [MiB/s] */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::StorageInformation` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==( + const CameraServer::StorageInformation& lhs, const CameraServer::StorageInformation& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::StorageInformation`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::StorageInformation const& storage_information); + + /** + * @brief + */ + struct CaptureStatus { + /** + * @brief + */ + enum class ImageStatus { + Idle, /**< @brief idle. */ + CaptureInProgress, /**< @brief capture in progress. */ + IntervalIdle, /**< @brief interval set but idle. */ + IntervalInProgress, /**< @brief interval set and capture in progress). */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::ImageStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::CaptureStatus::ImageStatus const& image_status); + + /** + * @brief + */ + enum class VideoStatus { + Idle, /**< @brief idle. */ + CaptureInProgress, /**< @brief capture in progress. */ + }; + + /** + * @brief Stream operator to print information about a `CameraServer::VideoStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::CaptureStatus::VideoStatus const& video_status); + + float image_interval{}; /**< @brief Image capture interval (in s) */ + float recording_time_s{}; /**< @brief Elapsed time since recording started (in s) */ + float available_capacity{}; /**< @brief Available storage capacity. (in MiB) */ + ImageStatus image_status{}; /**< @brief Current status of image capturing */ + VideoStatus video_status{}; /**< @brief Current status of video capturing */ + int32_t image_count{}; /**< @brief Total number of images captured ('forever', or until + reset using MAV_CMD_STORAGE_FORMAT) */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::CaptureStatus` objects. + * + * @return `true` if items are equal. + */ + friend bool + operator==(const CameraServer::CaptureStatus& lhs, const CameraServer::CaptureStatus& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::CaptureStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::CaptureStatus const& capture_status); + /** * @brief Callback type for asynchronous CameraServer calls. */ @@ -385,6 +518,67 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_set_mode(SetModeHandle handle); + /** + * @brief Callback type for subscribe_storage_information. + */ + using StorageInformationCallback = std::function; + + /** + * @brief Handle type for subscribe_storage_information. + */ + using StorageInformationHandle = Handle; + + /** + * @brief Subscribe to camera storage information requests. Each request received should + * response to using StorageInformationResponse + */ + StorageInformationHandle + subscribe_storage_information(const StorageInformationCallback& callback); + + /** + * @brief Unsubscribe from subscribe_storage_information + */ + void unsubscribe_storage_information(StorageInformationHandle handle); + + /** + * @brief Respond to camera storage information from SubscribeStorageInformation. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_storage_information(StorageInformation storage_information) const; + + /** + * @brief Callback type for subscribe_capture_status. + */ + using CaptureStatusCallback = std::function; + + /** + * @brief Handle type for subscribe_capture_status. + */ + using CaptureStatusHandle = Handle; + + /** + * @brief Subscribe to camera capture status requests. Each request received should response to + * using CaptureStatusResponse + */ + CaptureStatusHandle subscribe_capture_status(const CaptureStatusCallback& callback); + + /** + * @brief Unsubscribe from subscribe_capture_status + */ + void unsubscribe_capture_status(CaptureStatusHandle handle); + + /** + * @brief Respond to camera capture status from SubscribeCaptureStatus. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_capture_status(CaptureStatus capture_status) const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index 368fc170c8..6b2ce6ac87 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -33,6 +33,10 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation", + "/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus", + "/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -51,6 +55,10 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStorageInformation_(CameraServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -218,6 +226,84 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* Camer return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeSetMode_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* CameraServerService::Stub::SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StorageInformationResponse>::Create(channel_.get(), rpcmethod_SubscribeStorageInformation_, context, request); +} + +void CameraServerService::Stub::async::SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::StorageInformationResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeStorageInformation_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* CameraServerService::Stub::AsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StorageInformationResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStorageInformation_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* CameraServerService::Stub::PrepareAsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StorageInformationResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStorageInformation_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondStorageInformation_, context, request, response); +} + +void CameraServerService::Stub::async::RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStorageInformation_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStorageInformation_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* CameraServerService::Stub::PrepareAsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondStorageInformation_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* CameraServerService::Stub::AsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondStorageInformationRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* CameraServerService::Stub::SubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::CaptureStatusResponse>::Create(channel_.get(), rpcmethod_SubscribeCaptureStatus_, context, request); +} + +void CameraServerService::Stub::async::SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::CaptureStatusResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeCaptureStatus_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* CameraServerService::Stub::AsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::CaptureStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCaptureStatus_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* CameraServerService::Stub::PrepareAsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::CaptureStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCaptureStatus_, context, request, false, nullptr); +} + +::grpc::Status CameraServerService::Stub::RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondCaptureStatus_, context, request, response); +} + +void CameraServerService::Stub::async::RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondCaptureStatus_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondCaptureStatus_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* CameraServerService::Stub::PrepareAsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondCaptureStatus_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* CameraServerService::Stub::AsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondCaptureStatusRaw(context, request, cq); + result->StartCall(); + return result; +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -309,6 +395,46 @@ CameraServerService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::camera_server::SetModeResponse>* writer) { return service->SubscribeSetMode(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[9], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::StorageInformationResponse>* writer) { + return service->SubscribeStorageInformation(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[10], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* req, + ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* resp) { + return service->RespondStorageInformation(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[11], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer) { + return service->SubscribeCaptureStatus(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[12], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* req, + ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* resp) { + return service->RespondCaptureStatus(ctx, req, resp); + }, this))); } CameraServerService::Service::~Service() { @@ -377,6 +503,34 @@ ::grpc::Status CameraServerService::Service::SubscribeSetMode(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::RespondCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* 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/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index dfee6b6ac9..d30f7e9746 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -122,6 +122,42 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); } + // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>> SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(SubscribeStorageInformationRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>> AsyncSubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(AsyncSubscribeStorageInformationRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>> PrepareAsyncSubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(PrepareAsyncSubscribeStorageInformationRaw(context, request, cq)); + } + // Respond to camera storage information from SubscribeStorageInformation. + virtual ::grpc::Status RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>> AsyncRespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>>(AsyncRespondStorageInformationRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>> PrepareAsyncRespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>>(PrepareAsyncRespondStorageInformationRaw(context, request, cq)); + } + // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(SubscribeCaptureStatusRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> AsyncSubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(AsyncSubscribeCaptureStatusRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> PrepareAsyncSubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(PrepareAsyncSubscribeCaptureStatusRaw(context, request, cq)); + } + // Respond to camera capture status from SubscribeCaptureStatus. + virtual ::grpc::Status RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> AsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(AsyncRespondCaptureStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> PrepareAsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(PrepareAsyncRespondCaptureStatusRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -146,6 +182,16 @@ class CameraServerService final { virtual void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) = 0; // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse virtual void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) = 0; + // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + virtual void SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* reactor) = 0; + // Respond to camera storage information from SubscribeStorageInformation. + virtual void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, std::function) = 0; + virtual void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + virtual void SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* reactor) = 0; + // Respond to camera capture status from SubscribeCaptureStatus. + virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) = 0; + virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -175,6 +221,16 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* AsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* PrepareAsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* AsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* PrepareAsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* SubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* AsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* PrepareAsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* AsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* PrepareAsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -254,6 +310,38 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>> SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(SubscribeStorageInformationRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>> AsyncSubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(AsyncSubscribeStorageInformationRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>> PrepareAsyncSubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(PrepareAsyncSubscribeStorageInformationRaw(context, request, cq)); + } + ::grpc::Status RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>> AsyncRespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>>(AsyncRespondStorageInformationRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>> PrepareAsyncRespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>>(PrepareAsyncRespondStorageInformationRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(SubscribeCaptureStatusRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> AsyncSubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(AsyncSubscribeCaptureStatusRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> PrepareAsyncSubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(PrepareAsyncSubscribeCaptureStatusRaw(context, request, cq)); + } + ::grpc::Status RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> AsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(AsyncRespondCaptureStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> PrepareAsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(PrepareAsyncRespondCaptureStatusRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -269,6 +357,12 @@ class CameraServerService final { void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) override; void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) override; void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) override; + void SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* reactor) override; + void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, std::function) override; + void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* reactor) override; + void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) override; + void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -304,6 +398,16 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* AsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* PrepareAsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* AsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* PrepareAsyncRespondStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* SubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* AsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* PrepareAsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* AsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* PrepareAsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; @@ -313,6 +417,10 @@ class CameraServerService final { const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeSetMode_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeStorageInformation_; + const ::grpc::internal::RpcMethod rpcmethod_RespondStorageInformation_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeCaptureStatus_; + const ::grpc::internal::RpcMethod rpcmethod_RespondCaptureStatus_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -338,6 +446,14 @@ class CameraServerService final { virtual ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer); // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse virtual ::grpc::Status SubscribeSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer); + // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + virtual ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer); + // Respond to camera storage information from SubscribeStorageInformation. + virtual ::grpc::Status RespondStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response); + // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + virtual ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer); + // Respond to camera capture status from SubscribeCaptureStatus. + virtual ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -519,7 +635,87 @@ class CameraServerService final { ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodAsync(9); + } + ~WithAsyncMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodAsync(10); + } + ~WithAsyncMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodAsync(11); + } + ~WithAsyncMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodAsync(12); + } + ~WithAsyncMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(12, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -733,7 +929,105 @@ class CameraServerService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetMode( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > > CallbackService; + template + class WithCallbackMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request) { return this->SubscribeStorageInformation(context, request); })); + } + ~WithCallbackMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* SubscribeStorageInformation( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodCallback(10, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) { return this->RespondStorageInformation(context, request, response); }));} + void SetMessageAllocatorFor_RespondStorageInformation( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(10); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStorageInformation( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodCallback(11, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request) { return this->SubscribeCaptureStatus(context, request); })); + } + ~WithCallbackMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* SubscribeCaptureStatus( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodCallback(12, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) { return this->RespondCaptureStatus(context, request, response); }));} + void SetMessageAllocatorFor_RespondCaptureStatus( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(12); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondCaptureStatus( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -889,6 +1183,74 @@ class CameraServerService final { } }; template + class WithGenericMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodGeneric(9); + } + ~WithGenericMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodGeneric(10); + } + ~WithGenericMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodGeneric(11); + } + ~WithGenericMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodGeneric(12); + } + ~WithGenericMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1069,6 +1431,86 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodRaw(10); + } + ~WithRawMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStorageInformation(::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(10, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodRaw(11); + } + ~WithRawMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodRaw(12); + } + ~WithRawMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondCaptureStatus(::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(12, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1267,6 +1709,94 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodRawCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStorageInformation(context, request); })); + } + ~WithRawCallbackMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeStorageInformation( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodRawCallback(10, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStorageInformation(context, request, response); })); + } + ~WithRawCallbackMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStorageInformation( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodRawCallback(11, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCaptureStatus(context, request); })); + } + ~WithRawCallbackMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCaptureStatus( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodRawCallback(12, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondCaptureStatus(context, request, response); })); + } + ~WithRawCallbackMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondCaptureStatus( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1347,7 +1877,61 @@ class CameraServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedRespondTakePhoto(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest,::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetInformation > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_RespondStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondStorageInformation() { + ::grpc::Service::MarkMethodStreamed(10, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* streamer) { + return this->StreamedRespondStorageInformation(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondStorageInformation(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest,::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondCaptureStatus() { + ::grpc::Service::MarkMethodStreamed(12, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* streamer) { + return this->StreamedRespondCaptureStatus(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondCaptureStatus(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest,::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetInformation > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: @@ -1510,8 +2094,62 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeSetMode(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest,::mavsdk::rpc::camera_server::SetModeResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeStorageInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeStorageInformation() { + ::grpc::Service::MarkMethodStreamed(9, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>* streamer) { + return this->StreamedSubscribeStorageInformation(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeStorageInformation() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeStorageInformation(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest,::mavsdk::rpc::camera_server::StorageInformationResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeCaptureStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeCaptureStatus() { + ::grpc::Service::MarkMethodStreamed(11, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>* streamer) { + return this->StreamedSubscribeCaptureStatus(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeCaptureStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeCaptureStatus(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest,::mavsdk::rpc::camera_server::CaptureStatusResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 56b59e800f..a9b18986f3 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -260,6 +260,128 @@ struct SetModeResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest::SubscribeStorageInformationRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeStorageInformationRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeStorageInformationRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeStorageInformationRequestDefaultTypeInternal() {} + union { + SubscribeStorageInformationRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeStorageInformationRequestDefaultTypeInternal _SubscribeStorageInformationRequest_default_instance_; +template +PROTOBUF_CONSTEXPR StorageInformationResponse::StorageInformationResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.storage_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StorageInformationResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR StorageInformationResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StorageInformationResponseDefaultTypeInternal() {} + union { + StorageInformationResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StorageInformationResponseDefaultTypeInternal _StorageInformationResponse_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStorageInformationRequest::RespondStorageInformationRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.storage_information_)*/nullptr} {} +struct RespondStorageInformationRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStorageInformationRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStorageInformationRequestDefaultTypeInternal() {} + union { + RespondStorageInformationRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStorageInformationRequestDefaultTypeInternal _RespondStorageInformationRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStorageInformationResponse::RespondStorageInformationResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondStorageInformationResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStorageInformationResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStorageInformationResponseDefaultTypeInternal() {} + union { + RespondStorageInformationResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStorageInformationResponseDefaultTypeInternal _RespondStorageInformationResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeCaptureStatusRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeCaptureStatusRequestDefaultTypeInternal() {} + union { + SubscribeCaptureStatusRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeCaptureStatusRequestDefaultTypeInternal _SubscribeCaptureStatusRequest_default_instance_; +template +PROTOBUF_CONSTEXPR CaptureStatusResponse::CaptureStatusResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.reserved_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct CaptureStatusResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR CaptureStatusResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~CaptureStatusResponseDefaultTypeInternal() {} + union { + CaptureStatusResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CaptureStatusResponseDefaultTypeInternal _CaptureStatusResponse_default_instance_; +template +PROTOBUF_CONSTEXPR RespondCaptureStatusRequest::RespondCaptureStatusRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.capture_status_)*/nullptr} {} +struct RespondCaptureStatusRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondCaptureStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondCaptureStatusRequestDefaultTypeInternal() {} + union { + RespondCaptureStatusRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondCaptureStatusRequestDefaultTypeInternal _RespondCaptureStatusRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondCaptureStatusResponse::RespondCaptureStatusResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondCaptureStatusResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondCaptureStatusResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondCaptureStatusResponseDefaultTypeInternal() {} + union { + RespondCaptureStatusResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondCaptureStatusResponseDefaultTypeInternal _RespondCaptureStatusResponse_default_instance_; +template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -428,11 +550,67 @@ struct CameraServerResultDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraServerResultDefaultTypeInternal _CameraServerResult_default_instance_; +template +PROTOBUF_CONSTEXPR StorageInformation::StorageInformation( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.used_storage_mib_)*/ 0 + + , /*decltype(_impl_.available_storage_mib_)*/ 0 + + , /*decltype(_impl_.total_storage_mib_)*/ 0 + + , /*decltype(_impl_.storage_status_)*/ 0 + + , /*decltype(_impl_.storage_id_)*/ 0u + + , /*decltype(_impl_.storage_type_)*/ 0 + + , /*decltype(_impl_.read_speed_)*/ 0 + + , /*decltype(_impl_.write_speed_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct StorageInformationDefaultTypeInternal { + PROTOBUF_CONSTEXPR StorageInformationDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~StorageInformationDefaultTypeInternal() {} + union { + StorageInformation _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StorageInformationDefaultTypeInternal _StorageInformation_default_instance_; +template +PROTOBUF_CONSTEXPR CaptureStatus::CaptureStatus( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.image_interval_)*/ 0 + + , /*decltype(_impl_.recording_time_s_)*/ 0 + + , /*decltype(_impl_.available_capacity_)*/ 0 + + , /*decltype(_impl_.image_status_)*/ 0 + + , /*decltype(_impl_.video_status_)*/ 0 + + , /*decltype(_impl_.image_count_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct CaptureStatusDefaultTypeInternal { + PROTOBUF_CONSTEXPR CaptureStatusDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~CaptureStatusDefaultTypeInternal() {} + union { + CaptureStatus _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CaptureStatusDefaultTypeInternal _CaptureStatus_default_instance_; } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]; -static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]; +static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( @@ -578,6 +756,80 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetModeResponse, _impl_.mode_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, _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::camera_server::StorageInformationResponse, _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::camera_server::StorageInformationResponse, _impl_.storage_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _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::camera_server::RespondStorageInformationRequest, _impl_.storage_information_), + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _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::camera_server::RespondStorageInformationResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, _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::camera_server::CaptureStatusResponse, _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::camera_server::CaptureStatusResponse, _impl_.reserved_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _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::camera_server::RespondCaptureStatusRequest, _impl_.capture_status_), + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _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::camera_server::RespondCaptureStatusResponse, _impl_.camera_server_result_), + 0, PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -673,6 +925,36 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _impl_.result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CameraServerResult, _impl_.result_str_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _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::camera_server::StorageInformation, _impl_.used_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.available_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.total_storage_mib_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_type_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.read_speed_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.write_speed_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _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::camera_server::CaptureStatus, _impl_.image_interval_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.recording_time_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.available_capacity_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.video_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_count_), }; static const ::_pbi::MigrationSchema @@ -693,13 +975,23 @@ static const ::_pbi::MigrationSchema { 115, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, { 124, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, { 132, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, - { 141, 151, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 153, 162, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 163, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 182, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 194, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 206, 220, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 226, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 141, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, + { 149, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, + { 158, 167, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, + { 168, 177, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, + { 178, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, + { 186, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, + { 195, 204, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, + { 205, 214, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, + { 215, 225, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 227, 236, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 237, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 256, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 268, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 280, 294, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 300, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 310, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + { 326, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -719,6 +1011,14 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_StopVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeSetModeRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetModeResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeStorageInformationRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StorageInformationResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStorageInformationRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStorageInformationResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeCaptureStatusRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_CaptureStatusResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondCaptureStatusRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondCaptureStatusResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -726,6 +1026,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_Quaternion_default_instance_._instance, &::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_._instance, &::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_._instance, + &::mavsdk::rpc::camera_server::_StorageInformation_default_instance_._instance, + &::mavsdk::rpc::camera_server::_CaptureStatus_default_instance_._instance, }; const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n!camera_server/camera_server.proto\022\030mav" @@ -750,76 +1052,134 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "oStreamingResponse\022\021\n\tstream_id\030\001 \001(\005\"\031\n" "\027SubscribeSetModeRequest\"\?\n\017SetModeRespo" "nse\022,\n\004mode\030\001 \001(\0162\036.mavsdk.rpc.camera_se" - "rver.Mode\"\240\001\n\027RespondTakePhotoRequest\022H\n" - "\023take_photo_feedback\030\001 \001(\0162+.mavsdk.rpc." - "camera_server.TakePhotoFeedback\022;\n\014captu" - "re_info\030\002 \001(\0132%.mavsdk.rpc.camera_server" - ".CaptureInfo\"f\n\030RespondTakePhotoResponse" - "\022J\n\024camera_server_result\030\001 \001(\0132,.mavsdk." - "rpc.camera_server.CameraServerResult\"\276\002\n" - "\013Information\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmod" - "el_name\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022" - "\027\n\017focal_length_mm\030\004 \001(\002\022!\n\031horizontal_s" - "ensor_size_mm\030\005 \001(\002\022\037\n\027vertical_sensor_s" - "ize_mm\030\006 \001(\002\022 \n\030horizontal_resolution_px" - "\030\007 \001(\r\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017" - "\n\007lens_id\030\t \001(\r\022\037\n\027definition_file_versi" - "on\030\n \001(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n" - "\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongi" - "tude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 " - "\001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\nQuat" - "ernion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022" - "\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001" - " \001(\0132\".mavsdk.rpc.camera_server.Position" - "\022A\n\023attitude_quaternion\030\002 \001(\0132$.mavsdk.r" - "pc.camera_server.Quaternion\022\023\n\013time_utc_" - "us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 " - "\001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerRe" - "sult\022C\n\006result\030\001 \001(\01623.mavsdk.rpc.camera" - "_server.CameraServerResult.Result\022\022\n\nres" - "ult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNO" - "WN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PR" - "OGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENI" - "ED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT" - "\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_" - "NO_SYSTEM\020\010*\216\001\n\021TakePhotoFeedback\022\037\n\033TAK" - "E_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO" - "_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDBACK_BU" - "SY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_FAILED\020\003*8\n\004" - "Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016" - "\n\nMODE_VIDEO\020\0022\302\t\n\023CameraServerService\022y" - "\n\016SetInformation\022/.mavsdk.rpc.camera_ser" - "ver.SetInformationRequest\0320.mavsdk.rpc.c" - "amera_server.SetInformationResponse\"\004\200\265\030" - "\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_s" - "erver.SetInProgressRequest\032/.mavsdk.rpc." - "camera_server.SetInProgressResponse\"\004\200\265\030" - "\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.cam" - "era_server.SubscribeTakePhotoRequest\032+.m" - "avsdk.rpc.camera_server.TakePhotoRespons" - "e\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.r" - "pc.camera_server.RespondTakePhotoRequest" - "\0322.mavsdk.rpc.camera_server.RespondTakeP" - "hotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVid" - "eo\0224.mavsdk.rpc.camera_server.SubscribeS" - "tartVideoRequest\032,.mavsdk.rpc.camera_ser" - "ver.StartVideoResponse\"\004\200\265\030\0000\001\022~\n\022Subscr" - "ibeStopVideo\0223.mavsdk.rpc.camera_server." - "SubscribeStopVideoRequest\032+.mavsdk.rpc.c" - "amera_server.StopVideoResponse\"\004\200\265\030\0000\001\022\234" - "\001\n\034SubscribeStartVideoStreaming\022=.mavsdk" - ".rpc.camera_server.SubscribeStartVideoSt" - "reamingRequest\0325.mavsdk.rpc.camera_serve" - "r.StartVideoStreamingResponse\"\004\200\265\030\0000\001\022\231\001" - "\n\033SubscribeStopVideoStreaming\022<.mavsdk.r" - "pc.camera_server.SubscribeStopVideoStrea" - "mingRequest\0324.mavsdk.rpc.camera_server.S" - "topVideoStreamingResponse\"\004\200\265\030\0000\001\022x\n\020Sub" - "scribeSetMode\0221.mavsdk.rpc.camera_server" - ".SubscribeSetModeRequest\032).mavsdk.rpc.ca" - "mera_server.SetModeResponse\"\004\200\265\030\0000\001B,\n\027i" - "o.mavsdk.camera_serverB\021CameraServerProt" - "ob\006proto3" + "rver.Mode\"$\n\"SubscribeStorageInformation" + "Request\"0\n\032StorageInformationResponse\022\022\n" + "\nstorage_id\030\001 \001(\005\"m\n RespondStorageInfor" + "mationRequest\022I\n\023storage_information\030\001 \001" + "(\0132,.mavsdk.rpc.camera_server.StorageInf" + "ormation\"o\n!RespondStorageInformationRes" + "ponse\022J\n\024camera_server_result\030\001 \001(\0132,.ma" + "vsdk.rpc.camera_server.CameraServerResul" + "t\"\037\n\035SubscribeCaptureStatusRequest\")\n\025Ca" + "ptureStatusResponse\022\020\n\010reserved\030\001 \001(\005\"^\n" + "\033RespondCaptureStatusRequest\022\?\n\016capture_" + "status\030\001 \001(\0132\'.mavsdk.rpc.camera_server." + "CaptureStatus\"j\n\034RespondCaptureStatusRes" + "ponse\022J\n\024camera_server_result\030\001 \001(\0132,.ma" + "vsdk.rpc.camera_server.CameraServerResul" + "t\"\240\001\n\027RespondTakePhotoRequest\022H\n\023take_ph" + "oto_feedback\030\001 \001(\0162+.mavsdk.rpc.camera_s" + "erver.TakePhotoFeedback\022;\n\014capture_info\030" + "\002 \001(\0132%.mavsdk.rpc.camera_server.Capture" + "Info\"f\n\030RespondTakePhotoResponse\022J\n\024came" + "ra_server_result\030\001 \001(\0132,.mavsdk.rpc.came" + "ra_server.CameraServerResult\"\276\002\n\013Informa" + "tion\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030" + "\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal" + "_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_si" + "ze_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006" + " \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036" + "\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens_i" + "d\030\t \001(\r\022\037\n\027definition_file_version\030\n \001(\r" + "\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Positio" + "n\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg" + "\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023r" + "elative_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t" + "\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001" + "(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".m" + "avsdk.rpc.camera_server.Position\022A\n\023atti" + "tude_quaternion\030\002 \001(\0132$.mavsdk.rpc.camer" + "a_server.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004" + "\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010f" + "ile_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006" + "result\030\001 \001(\01623.mavsdk.rpc.camera_server." + "CameraServerResult.Result\022\022\n\nresult_str\030" + "\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" + "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" + "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" + "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" + "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" + "M\020\010\"\200\005\n\022StorageInformation\022\030\n\020used_stora" + "ge_mib\030\001 \001(\002\022\035\n\025available_storage_mib\030\002 " + "\001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016storag" + "e_status\030\004 \001(\0162:.mavsdk.rpc.camera_serve" + "r.StorageInformation.StorageStatus\022\022\n\nst" + "orage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628.m" + "avsdk.rpc.camera_server.StorageInformati" + "on.StorageType\022\022\n\nread_speed\030\007 \001(\002\022\023\n\013wr" + "ite_speed\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STO" + "RAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_S" + "TATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FO" + "RMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTE" + "D\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKN" + "OWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STO" + "RAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003" + "\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OT" + "HER\020\376\001\"\350\003\n\rCaptureStatus\022\026\n\016image_interv" + "al\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\032\n\022av" + "ailable_capacity\030\003 \001(\002\022I\n\014image_status\030\004" + " \001(\01623.mavsdk.rpc.camera_server.CaptureS" + "tatus.ImageStatus\022I\n\014video_status\030\005 \001(\0162" + "3.mavsdk.rpc.camera_server.CaptureStatus" + ".VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013Im" + "ageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMAG" + "E_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE_" + "STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_I" + "NTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n\021" + "VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAPT" + "URE_IN_PROGRESS\020\001*\216\001\n\021TakePhotoFeedback\022" + "\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE" + "_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDB" + "ACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_FAILED" + "\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHO" + "TO\020\001\022\016\n\nMODE_VIDEO\020\0022\226\016\n\023CameraServerSer" + "vice\022y\n\016SetInformation\022/.mavsdk.rpc.came" + "ra_server.SetInformationRequest\0320.mavsdk" + ".rpc.camera_server.SetInformationRespons" + "e\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.ca" + "mera_server.SetInProgressRequest\032/.mavsd" + "k.rpc.camera_server.SetInProgressRespons" + "e\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.r" + "pc.camera_server.SubscribeTakePhotoReque" + "st\032+.mavsdk.rpc.camera_server.TakePhotoR" + "esponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.ma" + "vsdk.rpc.camera_server.RespondTakePhotoR" + "equest\0322.mavsdk.rpc.camera_server.Respon" + "dTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeSt" + "artVideo\0224.mavsdk.rpc.camera_server.Subs" + "cribeStartVideoRequest\032,.mavsdk.rpc.came" + "ra_server.StartVideoResponse\"\004\200\265\030\0000\001\022~\n\022" + "SubscribeStopVideo\0223.mavsdk.rpc.camera_s" + "erver.SubscribeStopVideoRequest\032+.mavsdk" + ".rpc.camera_server.StopVideoResponse\"\004\200\265" + "\030\0000\001\022\234\001\n\034SubscribeStartVideoStreaming\022=." + "mavsdk.rpc.camera_server.SubscribeStartV" + "ideoStreamingRequest\0325.mavsdk.rpc.camera" + "_server.StartVideoStreamingResponse\"\004\200\265\030" + "\0000\001\022\231\001\n\033SubscribeStopVideoStreaming\022<.ma" + "vsdk.rpc.camera_server.SubscribeStopVide" + "oStreamingRequest\0324.mavsdk.rpc.camera_se" + "rver.StopVideoStreamingResponse\"\004\200\265\030\0000\001\022" + "x\n\020SubscribeSetMode\0221.mavsdk.rpc.camera_" + "server.SubscribeSetModeRequest\032).mavsdk." + "rpc.camera_server.SetModeResponse\"\004\200\265\030\0000" + "\001\022\231\001\n\033SubscribeStorageInformation\022<.mavs" + "dk.rpc.camera_server.SubscribeStorageInf" + "ormationRequest\0324.mavsdk.rpc.camera_serv" + "er.StorageInformationResponse\"\004\200\265\030\0000\001\022\232\001" + "\n\031RespondStorageInformation\022:.mavsdk.rpc" + ".camera_server.RespondStorageInformation" + "Request\032;.mavsdk.rpc.camera_server.Respo" + "ndStorageInformationResponse\"\004\200\265\030\001\022\212\001\n\026S" + "ubscribeCaptureStatus\0227.mavsdk.rpc.camer" + "a_server.SubscribeCaptureStatusRequest\032/" + ".mavsdk.rpc.camera_server.CaptureStatusR" + "esponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondCaptureStatus" + "\0225.mavsdk.rpc.camera_server.RespondCaptu" + "reStatusRequest\0326.mavsdk.rpc.camera_serv" + "er.RespondCaptureStatusResponse\"\004\200\265\030\001B,\n" + "\027io.mavsdk.camera_serverB\021CameraServerPr" + "otob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -829,13 +1189,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 3649, + 5971, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 23, + 33, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -902,10 +1262,122 @@ constexpr int CameraServerResult::Result_ARRAYSIZE; #endif // (__cplusplus < 201703) && // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) -const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* TakePhotoFeedback_descriptor() { +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageInformation_StorageStatus_descriptor() { ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[1]; } +bool StorageInformation_StorageStatus_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr StorageInformation_StorageStatus StorageInformation::STORAGE_STATUS_NOT_AVAILABLE; +constexpr StorageInformation_StorageStatus StorageInformation::STORAGE_STATUS_UNFORMATTED; +constexpr StorageInformation_StorageStatus StorageInformation::STORAGE_STATUS_FORMATTED; +constexpr StorageInformation_StorageStatus StorageInformation::STORAGE_STATUS_NOT_SUPPORTED; +constexpr StorageInformation_StorageStatus StorageInformation::StorageStatus_MIN; +constexpr StorageInformation_StorageStatus StorageInformation::StorageStatus_MAX; +constexpr int StorageInformation::StorageStatus_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageInformation_StorageType_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; +} +bool StorageInformation_StorageType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 7: + case 254: + return true; + default: + return false; + } +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_UNKNOWN; +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_USB_STICK; +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_SD; +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_MICROSD; +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_HD; +constexpr StorageInformation_StorageType StorageInformation::STORAGE_TYPE_OTHER; +constexpr StorageInformation_StorageType StorageInformation::StorageType_MIN; +constexpr StorageInformation_StorageType StorageInformation::StorageType_MAX; +constexpr int StorageInformation::StorageType_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* CaptureStatus_ImageStatus_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[3]; +} +bool CaptureStatus_ImageStatus_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr CaptureStatus_ImageStatus CaptureStatus::IMAGE_STATUS_IDLE; +constexpr CaptureStatus_ImageStatus CaptureStatus::IMAGE_STATUS_CAPTURE_IN_PROGRESS; +constexpr CaptureStatus_ImageStatus CaptureStatus::IMAGE_STATUS_INTERVAL_IDLE; +constexpr CaptureStatus_ImageStatus CaptureStatus::IMAGE_STATUS_INTERVAL_IN_PROGRESS; +constexpr CaptureStatus_ImageStatus CaptureStatus::ImageStatus_MIN; +constexpr CaptureStatus_ImageStatus CaptureStatus::ImageStatus_MAX; +constexpr int CaptureStatus::ImageStatus_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* CaptureStatus_VideoStatus_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[4]; +} +bool CaptureStatus_VideoStatus_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} +#if (__cplusplus < 201703) && \ + (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) + +constexpr CaptureStatus_VideoStatus CaptureStatus::VIDEO_STATUS_IDLE; +constexpr CaptureStatus_VideoStatus CaptureStatus::VIDEO_STATUS_CAPTURE_IN_PROGRESS; +constexpr CaptureStatus_VideoStatus CaptureStatus::VideoStatus_MIN; +constexpr CaptureStatus_VideoStatus CaptureStatus::VideoStatus_MAX; +constexpr int CaptureStatus::VideoStatus_ARRAYSIZE; + +#endif // (__cplusplus < 201703) && + // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* TakePhotoFeedback_descriptor() { + ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; +} bool TakePhotoFeedback_IsValid(int value) { switch (value) { case 0: @@ -919,7 +1391,7 @@ bool TakePhotoFeedback_IsValid(int value) { } const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Mode_descriptor() { ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); - return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[2]; + return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[6]; } bool Mode_IsValid(int value) { switch (value) { @@ -2993,57 +3465,71 @@ ::PROTOBUF_NAMESPACE_ID::Metadata SetModeResponse::GetMetadata() const { } // =================================================================== -class RespondTakePhotoRequest::_Internal { +class SubscribeStorageInformationRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const RespondTakePhotoRequest* msg); - static void set_has_capture_info(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::CaptureInfo& -RespondTakePhotoRequest::_Internal::capture_info(const RespondTakePhotoRequest* msg) { - return *msg->_impl_.capture_info_; +SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) } -RespondTakePhotoRequest::RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStorageInformationRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStorageInformationRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStorageInformationRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStorageInformationRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); +} +// =================================================================== + +class StorageInformationResponse::_Internal { + public: +}; + +StorageInformationResponse::StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) } -RespondTakePhotoRequest::RespondTakePhotoRequest(const RespondTakePhotoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondTakePhotoRequest* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_info_){nullptr} - , decltype(_impl_.take_photo_feedback_) {} - }; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.capture_info_ = new ::mavsdk::rpc::camera_server::CaptureInfo(*from._impl_.capture_info_); - } - _this->_impl_.take_photo_feedback_ = from._impl_.take_photo_feedback_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +StorageInformationResponse::StorageInformationResponse(const StorageInformationResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) } -inline void RespondTakePhotoRequest::SharedCtor(::_pb::Arena* arena) { +inline void StorageInformationResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_info_){nullptr} - , decltype(_impl_.take_photo_feedback_) { 0 } + decltype(_impl_.storage_id_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} }; } -RespondTakePhotoRequest::~RespondTakePhotoRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +StorageInformationResponse::~StorageInformationResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StorageInformationResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3051,52 +3537,34 @@ RespondTakePhotoRequest::~RespondTakePhotoRequest() { SharedDtor(); } -inline void RespondTakePhotoRequest::SharedDtor() { +inline void StorageInformationResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.capture_info_; } -void RespondTakePhotoRequest::SetCachedSize(int size) const { +void StorageInformationResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondTakePhotoRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +void StorageInformationResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StorageInformationResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.capture_info_ != nullptr); - _impl_.capture_info_->Clear(); - } - _impl_.take_photo_feedback_ = 0; - _impl_._has_bits_.Clear(); + _impl_.storage_id_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* StorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + // int32 storage_id = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - _internal_set_take_photo_feedback(static_cast<::mavsdk::rpc::camera_server::TakePhotoFeedback>(val)); - } else { - goto handle_unusual; - } - continue; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - ptr = ctx->ParseMessage(_internal_mutable_capture_info(), ptr); + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else { goto handle_unusual; @@ -3118,7 +3586,6 @@ const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::Par CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -3126,161 +3593,136 @@ const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::Par #undef CHK_ } -::uint8_t* RespondTakePhotoRequest::_InternalSerialize( +::uint8_t* StorageInformationResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StorageInformationResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - if (this->_internal_take_photo_feedback() != 0) { + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_take_photo_feedback(), target); - } - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(2, _Internal::capture_info(this), - _Internal::capture_info(this).GetCachedSize(), target, stream); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_storage_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.StorageInformationResponse) return target; } -::size_t RespondTakePhotoRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +::size_t StorageInformationResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StorageInformationResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.capture_info_); - } - - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - if (this->_internal_take_photo_feedback() != 0) { - total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_take_photo_feedback()); + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StorageInformationResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondTakePhotoRequest::MergeImpl + StorageInformationResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StorageInformationResponse::GetClassData() const { return &_class_data_; } -void RespondTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoRequest) +void StorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StorageInformationResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_capture_info()->::mavsdk::rpc::camera_server::CaptureInfo::MergeFrom( - from._internal_capture_info()); - } - if (from._internal_take_photo_feedback() != 0) { - _this->_internal_set_take_photo_feedback(from._internal_take_photo_feedback()); + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondTakePhotoRequest::CopyFrom(const RespondTakePhotoRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +void StorageInformationResponse::CopyFrom(const StorageInformationResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StorageInformationResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondTakePhotoRequest::IsInitialized() const { +bool StorageInformationResponse::IsInitialized() const { return true; } -void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { +void StorageInformationResponse::InternalSwap(StorageInformationResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.take_photo_feedback_) - + sizeof(RespondTakePhotoRequest::_impl_.take_photo_feedback_) - - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.capture_info_)>( - reinterpret_cast(&_impl_.capture_info_), - reinterpret_cast(&other->_impl_.capture_info_)); + + swap(_impl_.storage_id_, other->_impl_.storage_id_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata StorageInformationResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); } // =================================================================== -class RespondTakePhotoResponse::_Internal { +class RespondStorageInformationRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondTakePhotoResponse* msg); - static void set_has_camera_server_result(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::StorageInformation& storage_information(const RespondStorageInformationRequest* msg); + static void set_has_storage_information(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera_server::CameraServerResult& -RespondTakePhotoResponse::_Internal::camera_server_result(const RespondTakePhotoResponse* msg) { - return *msg->_impl_.camera_server_result_; +const ::mavsdk::rpc::camera_server::StorageInformation& +RespondStorageInformationRequest::_Internal::storage_information(const RespondStorageInformationRequest* msg) { + return *msg->_impl_.storage_information_; } -RespondTakePhotoResponse::RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStorageInformationRequest::RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) } -RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoResponse& from) +RespondStorageInformationRequest::RespondStorageInformationRequest(const RespondStorageInformationRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondTakePhotoResponse* const _this = this; (void)_this; + RespondStorageInformationRequest* const _this = this; (void)_this; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){from._impl_._has_bits_} , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.camera_server_result_){nullptr}}; + , decltype(_impl_.storage_information_){nullptr}}; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + _this->_impl_.storage_information_ = new ::mavsdk::rpc::camera_server::StorageInformation(*from._impl_.storage_information_); } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) } -inline void RespondTakePhotoResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondStorageInformationRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.camera_server_result_){nullptr} + , decltype(_impl_.storage_information_){nullptr} }; } -RespondTakePhotoResponse::~RespondTakePhotoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +RespondStorageInformationRequest::~RespondStorageInformationRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3288,41 +3730,41 @@ RespondTakePhotoResponse::~RespondTakePhotoResponse() { SharedDtor(); } -inline void RespondTakePhotoResponse::SharedDtor() { +inline void RespondStorageInformationRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.camera_server_result_; + if (this != internal_default_instance()) delete _impl_.storage_information_; } -void RespondTakePhotoResponse::SetCachedSize(int size) const { +void RespondStorageInformationRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondTakePhotoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +void RespondStorageInformationRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); - _impl_.camera_server_result_->Clear(); + ABSL_DCHECK(_impl_.storage_information_ != nullptr); + _impl_.storage_information_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondStorageInformationRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + ptr = ctx->ParseMessage(_internal_mutable_storage_information(), ptr); CHK_(ptr); } else { goto handle_unusual; @@ -3352,213 +3794,364 @@ const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::Pa #undef CHK_ } -::uint8_t* RespondTakePhotoResponse::_InternalSerialize( +::uint8_t* RespondStorageInformationRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; if (cached_has_bits & 0x00000001u) { target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::camera_server_result(this), - _Internal::camera_server_result(this).GetCachedSize(), target, stream); + InternalWriteMessage(1, _Internal::storage_information(this), + _Internal::storage_information(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStorageInformationRequest) return target; } -::size_t RespondTakePhotoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +::size_t RespondStorageInformationRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.camera_server_result_); + *_impl_.storage_information_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondTakePhotoResponse::MergeImpl + RespondStorageInformationRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationRequest::GetClassData() const { return &_class_data_; } -void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoResponse) +void RespondStorageInformationRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( - from._internal_camera_server_result()); + _this->_internal_mutable_storage_information()->::mavsdk::rpc::camera_server::StorageInformation::MergeFrom( + from._internal_storage_information()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondTakePhotoResponse::CopyFrom(const RespondTakePhotoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +void RespondStorageInformationRequest::CopyFrom(const RespondStorageInformationRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondTakePhotoResponse::IsInitialized() const { +bool RespondStorageInformationRequest::IsInitialized() const { return true; } -void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { +void RespondStorageInformationRequest::InternalSwap(RespondStorageInformationRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); + swap(_impl_.storage_information_, other->_impl_.storage_information_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); } // =================================================================== -class Information::_Internal { +class RespondStorageInformationResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStorageInformationResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -Information::Information(::PROTOBUF_NAMESPACE_ID::Arena* arena) +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondStorageInformationResponse::_Internal::camera_server_result(const RespondStorageInformationResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondStorageInformationResponse::RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Information) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) } -Information::Information(const Information& from) +RespondStorageInformationResponse::RespondStorageInformationResponse(const RespondStorageInformationResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - Information* const _this = this; (void)_this; + RespondStorageInformationResponse* const _this = this; (void)_this; new (&_impl_) Impl_{ - decltype(_impl_.vendor_name_) {} + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; - , decltype(_impl_.model_name_) {} + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +} - , decltype(_impl_.firmware_version_) {} +inline void RespondStorageInformationResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} - , decltype(_impl_.definition_file_uri_) {} +RespondStorageInformationResponse::~RespondStorageInformationResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} - , decltype(_impl_.focal_length_mm_) {} +inline void RespondStorageInformationResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} - , decltype(_impl_.horizontal_sensor_size_mm_) {} +void RespondStorageInformationResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} - , decltype(_impl_.vertical_sensor_size_mm_) {} +void RespondStorageInformationResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; - , decltype(_impl_.horizontal_resolution_px_) {} + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} - , decltype(_impl_.vertical_resolution_px_) {} - - , decltype(_impl_.lens_id_) {} - - , decltype(_impl_.definition_file_version_) {} +const char* RespondStorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} - , /*decltype(_impl_._cached_size_)*/{}}; +::uint8_t* RespondStorageInformationResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.vendor_name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.vendor_name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_vendor_name().empty()) { - _this->_impl_.vendor_name_.Set(from._internal_vendor_name(), _this->GetArenaForAllocation()); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); } - _impl_.model_name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.model_name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_model_name().empty()) { - _this->_impl_.model_name_.Set(from._internal_model_name(), _this->GetArenaForAllocation()); + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - _impl_.firmware_version_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.firmware_version_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_firmware_version().empty()) { - _this->_impl_.firmware_version_.Set(from._internal_firmware_version(), _this->GetArenaForAllocation()); + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + return target; +} + +::size_t RespondStorageInformationResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); } - _impl_.definition_file_uri_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.definition_file_uri_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_definition_file_uri().empty()) { - _this->_impl_.definition_file_uri_.Set(from._internal_definition_file_uri(), _this->GetArenaForAllocation()); + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStorageInformationResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationResponse::GetClassData() const { return &_class_data_; } + + +void RespondStorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); } - ::memcpy(&_impl_.focal_length_mm_, &from._impl_.focal_length_mm_, - static_cast<::size_t>(reinterpret_cast(&_impl_.definition_file_version_) - - reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.definition_file_version_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Information) + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -inline void Information::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.vendor_name_) {} +void RespondStorageInformationResponse::CopyFrom(const RespondStorageInformationResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} - , decltype(_impl_.model_name_) {} +bool RespondStorageInformationResponse::IsInitialized() const { + return true; +} - , decltype(_impl_.firmware_version_) {} +void RespondStorageInformationResponse::InternalSwap(RespondStorageInformationResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} - , decltype(_impl_.definition_file_uri_) {} +::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); +} +// =================================================================== - , decltype(_impl_.focal_length_mm_) { 0 } +class SubscribeCaptureStatusRequest::_Internal { + public: +}; - , decltype(_impl_.horizontal_sensor_size_mm_) { 0 } +SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) +} +SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeCaptureStatusRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) +} - , decltype(_impl_.vertical_sensor_size_mm_) { 0 } - , decltype(_impl_.horizontal_resolution_px_) { 0u } - , decltype(_impl_.vertical_resolution_px_) { 0u } - , decltype(_impl_.lens_id_) { 0u } - , decltype(_impl_.definition_file_version_) { 0u } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeCaptureStatusRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeCaptureStatusRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeCaptureStatusRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); +} +// =================================================================== + +class CaptureStatusResponse::_Internal { + public: +}; + +CaptureStatusResponse::CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) +} +CaptureStatusResponse::CaptureStatusResponse(const CaptureStatusResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) +} + +inline void CaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.reserved_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; - _impl_.vendor_name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.vendor_name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.model_name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.model_name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.firmware_version_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.firmware_version_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.definition_file_uri_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.definition_file_uri_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -Information::~Information() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Information) +CaptureStatusResponse::~CaptureStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureStatusResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3566,143 +4159,1991 @@ Information::~Information() { SharedDtor(); } -inline void Information::SharedDtor() { +inline void CaptureStatusResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.vendor_name_.Destroy(); - _impl_.model_name_.Destroy(); - _impl_.firmware_version_.Destroy(); - _impl_.definition_file_uri_.Destroy(); } -void Information::SetCachedSize(int size) const { +void CaptureStatusResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void Information::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Information) +void CaptureStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureStatusResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.vendor_name_.ClearToEmpty(); - _impl_.model_name_.ClearToEmpty(); - _impl_.firmware_version_.ClearToEmpty(); - _impl_.definition_file_uri_.ClearToEmpty(); - ::memset(&_impl_.focal_length_mm_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.definition_file_version_) - - reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.definition_file_version_)); + _impl_.reserved_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* Information::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* CaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // string vendor_name = 1; + // int32 reserved = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - auto str = _internal_mutable_vendor_name(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.vendor_name")); - } else { - goto handle_unusual; - } - continue; - // string model_name = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - auto str = _internal_mutable_model_name(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.model_name")); - } else { - goto handle_unusual; - } - continue; - // string firmware_version = 3; - case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 26)) { - auto str = _internal_mutable_firmware_version(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.reserved_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.firmware_version")); } else { goto handle_unusual; } continue; - // float focal_length_mm = 4; - case 4: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { - _impl_.focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* CaptureStatusResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_reserved(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.CaptureStatusResponse) + return target; +} + +::size_t CaptureStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureStatusResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + CaptureStatusResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureStatusResponse::GetClassData() const { return &_class_data_; } + + +void CaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureStatusResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void CaptureStatusResponse::CopyFrom(const CaptureStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CaptureStatusResponse::IsInitialized() const { + return true; +} + +void CaptureStatusResponse::InternalSwap(CaptureStatusResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatusResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); +} +// =================================================================== + +class RespondCaptureStatusRequest::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status(const RespondCaptureStatusRequest* msg); + static void set_has_capture_status(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CaptureStatus& +RespondCaptureStatusRequest::_Internal::capture_status(const RespondCaptureStatusRequest* msg) { + return *msg->_impl_.capture_status_; +} +RespondCaptureStatusRequest::RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +} +RespondCaptureStatusRequest::RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondCaptureStatusRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_status_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.capture_status_ = new ::mavsdk::rpc::camera_server::CaptureStatus(*from._impl_.capture_status_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +} + +inline void RespondCaptureStatusRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_status_){nullptr} + }; +} + +RespondCaptureStatusRequest::~RespondCaptureStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondCaptureStatusRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.capture_status_; +} + +void RespondCaptureStatusRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondCaptureStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.capture_status_ != nullptr); + _impl_.capture_status_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondCaptureStatusRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_capture_status(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondCaptureStatusRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::capture_status(this), + _Internal::capture_status(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondCaptureStatusRequest) + return target; +} + +::size_t RespondCaptureStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.capture_status_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondCaptureStatusRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusRequest::GetClassData() const { return &_class_data_; } + + +void RespondCaptureStatusRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_capture_status()->::mavsdk::rpc::camera_server::CaptureStatus::MergeFrom( + from._internal_capture_status()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondCaptureStatusRequest::CopyFrom(const RespondCaptureStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondCaptureStatusRequest::IsInitialized() const { + return true; +} + +void RespondCaptureStatusRequest::InternalSwap(RespondCaptureStatusRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.capture_status_, other->_impl_.capture_status_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); +} +// =================================================================== + +class RespondCaptureStatusResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondCaptureStatusResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondCaptureStatusResponse::_Internal::camera_server_result(const RespondCaptureStatusResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondCaptureStatusResponse::RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +} +RespondCaptureStatusResponse::RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondCaptureStatusResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +} + +inline void RespondCaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondCaptureStatusResponse::~RespondCaptureStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondCaptureStatusResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondCaptureStatusResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondCaptureStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondCaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondCaptureStatusResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondCaptureStatusResponse) + return target; +} + +::size_t RespondCaptureStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondCaptureStatusResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusResponse::GetClassData() const { return &_class_data_; } + + +void RespondCaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondCaptureStatusResponse::CopyFrom(const RespondCaptureStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondCaptureStatusResponse::IsInitialized() const { + return true; +} + +void RespondCaptureStatusResponse::InternalSwap(RespondCaptureStatusResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]); +} +// =================================================================== + +class RespondTakePhotoRequest::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const RespondTakePhotoRequest* msg); + static void set_has_capture_info(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CaptureInfo& +RespondTakePhotoRequest::_Internal::capture_info(const RespondTakePhotoRequest* msg) { + return *msg->_impl_.capture_info_; +} +RespondTakePhotoRequest::RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +} +RespondTakePhotoRequest::RespondTakePhotoRequest(const RespondTakePhotoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondTakePhotoRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_info_){nullptr} + , decltype(_impl_.take_photo_feedback_) {} + }; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.capture_info_ = new ::mavsdk::rpc::camera_server::CaptureInfo(*from._impl_.capture_info_); + } + _this->_impl_.take_photo_feedback_ = from._impl_.take_photo_feedback_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +} + +inline void RespondTakePhotoRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_info_){nullptr} + , decltype(_impl_.take_photo_feedback_) { 0 } + + }; +} + +RespondTakePhotoRequest::~RespondTakePhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondTakePhotoRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.capture_info_; +} + +void RespondTakePhotoRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondTakePhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.capture_info_ != nullptr); + _impl_.capture_info_->Clear(); + } + _impl_.take_photo_feedback_ = 0; + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_take_photo_feedback(static_cast<::mavsdk::rpc::camera_server::TakePhotoFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_capture_info(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondTakePhotoRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + if (this->_internal_take_photo_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_take_photo_feedback(), target); + } + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(2, _Internal::capture_info(this), + _Internal::capture_info(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondTakePhotoRequest) + return target; +} + +::size_t RespondTakePhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.capture_info_); + } + + // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + if (this->_internal_take_photo_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_take_photo_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondTakePhotoRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoRequest::GetClassData() const { return &_class_data_; } + + +void RespondTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_capture_info()->::mavsdk::rpc::camera_server::CaptureInfo::MergeFrom( + from._internal_capture_info()); + } + if (from._internal_take_photo_feedback() != 0) { + _this->_internal_set_take_photo_feedback(from._internal_take_photo_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondTakePhotoRequest::CopyFrom(const RespondTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondTakePhotoRequest::IsInitialized() const { + return true; +} + +void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.take_photo_feedback_) + + sizeof(RespondTakePhotoRequest::_impl_.take_photo_feedback_) + - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.capture_info_)>( + reinterpret_cast(&_impl_.capture_info_), + reinterpret_cast(&other->_impl_.capture_info_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); +} +// =================================================================== + +class RespondTakePhotoResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondTakePhotoResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondTakePhotoResponse::_Internal::camera_server_result(const RespondTakePhotoResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondTakePhotoResponse::RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +} +RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondTakePhotoResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +} + +inline void RespondTakePhotoResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondTakePhotoResponse::~RespondTakePhotoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondTakePhotoResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondTakePhotoResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondTakePhotoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondTakePhotoResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondTakePhotoResponse) + return target; +} + +::size_t RespondTakePhotoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondTakePhotoResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoResponse::GetClassData() const { return &_class_data_; } + + +void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondTakePhotoResponse::CopyFrom(const RespondTakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondTakePhotoResponse::IsInitialized() const { + return true; +} + +void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); +} +// =================================================================== + +class Information::_Internal { + public: +}; + +Information::Information(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Information) +} +Information::Information(const Information& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + Information* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.vendor_name_) {} + + , decltype(_impl_.model_name_) {} + + , decltype(_impl_.firmware_version_) {} + + , decltype(_impl_.definition_file_uri_) {} + + , decltype(_impl_.focal_length_mm_) {} + + , decltype(_impl_.horizontal_sensor_size_mm_) {} + + , decltype(_impl_.vertical_sensor_size_mm_) {} + + , decltype(_impl_.horizontal_resolution_px_) {} + + , decltype(_impl_.vertical_resolution_px_) {} + + , decltype(_impl_.lens_id_) {} + + , decltype(_impl_.definition_file_version_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.vendor_name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.vendor_name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_vendor_name().empty()) { + _this->_impl_.vendor_name_.Set(from._internal_vendor_name(), _this->GetArenaForAllocation()); + } + _impl_.model_name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.model_name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_model_name().empty()) { + _this->_impl_.model_name_.Set(from._internal_model_name(), _this->GetArenaForAllocation()); + } + _impl_.firmware_version_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.firmware_version_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_firmware_version().empty()) { + _this->_impl_.firmware_version_.Set(from._internal_firmware_version(), _this->GetArenaForAllocation()); + } + _impl_.definition_file_uri_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.definition_file_uri_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_definition_file_uri().empty()) { + _this->_impl_.definition_file_uri_.Set(from._internal_definition_file_uri(), _this->GetArenaForAllocation()); + } + ::memcpy(&_impl_.focal_length_mm_, &from._impl_.focal_length_mm_, + static_cast<::size_t>(reinterpret_cast(&_impl_.definition_file_version_) - + reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.definition_file_version_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Information) +} + +inline void Information::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.vendor_name_) {} + + , decltype(_impl_.model_name_) {} + + , decltype(_impl_.firmware_version_) {} + + , decltype(_impl_.definition_file_uri_) {} + + , decltype(_impl_.focal_length_mm_) { 0 } + + , decltype(_impl_.horizontal_sensor_size_mm_) { 0 } + + , decltype(_impl_.vertical_sensor_size_mm_) { 0 } + + , decltype(_impl_.horizontal_resolution_px_) { 0u } + + , decltype(_impl_.vertical_resolution_px_) { 0u } + + , decltype(_impl_.lens_id_) { 0u } + + , decltype(_impl_.definition_file_version_) { 0u } + + , /*decltype(_impl_._cached_size_)*/{} + }; + _impl_.vendor_name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.vendor_name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.model_name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.model_name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.firmware_version_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.firmware_version_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.definition_file_uri_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.definition_file_uri_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING +} + +Information::~Information() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Information) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void Information::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.vendor_name_.Destroy(); + _impl_.model_name_.Destroy(); + _impl_.firmware_version_.Destroy(); + _impl_.definition_file_uri_.Destroy(); +} + +void Information::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void Information::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Information) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.vendor_name_.ClearToEmpty(); + _impl_.model_name_.ClearToEmpty(); + _impl_.firmware_version_.ClearToEmpty(); + _impl_.definition_file_uri_.ClearToEmpty(); + ::memset(&_impl_.focal_length_mm_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.definition_file_version_) - + reinterpret_cast(&_impl_.focal_length_mm_)) + sizeof(_impl_.definition_file_version_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Information::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // string vendor_name = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + auto str = _internal_mutable_vendor_name(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.vendor_name")); + } else { + goto handle_unusual; + } + continue; + // string model_name = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + auto str = _internal_mutable_model_name(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.model_name")); + } else { + goto handle_unusual; + } + continue; + // string firmware_version = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 26)) { + auto str = _internal_mutable_firmware_version(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.firmware_version")); + } else { + goto handle_unusual; + } + continue; + // float focal_length_mm = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { + _impl_.focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float horizontal_sensor_size_mm = 5; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 45)) { + _impl_.horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float vertical_sensor_size_mm = 6; + case 6: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 53)) { + _impl_.vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // uint32 horizontal_resolution_px = 7; + case 7: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 56)) { + _impl_.horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // uint32 vertical_resolution_px = 8; + case 8: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 64)) { + _impl_.vertical_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // uint32 lens_id = 9; + case 9: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 72)) { + _impl_.lens_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // uint32 definition_file_version = 10; + case 10: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 80)) { + _impl_.definition_file_version_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // string definition_file_uri = 11; + case 11: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 90)) { + auto str = _internal_mutable_definition_file_uri(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.definition_file_uri")); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* Information::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Information) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // string vendor_name = 1; + if (!this->_internal_vendor_name().empty()) { + const std::string& _s = this->_internal_vendor_name(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.vendor_name"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // string model_name = 2; + if (!this->_internal_model_name().empty()) { + const std::string& _s = this->_internal_model_name(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.model_name"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + const std::string& _s = this->_internal_firmware_version(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.firmware_version"); + target = stream->WriteStringMaybeAliased(3, _s, target); + } + + // float focal_length_mm = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_focal_length_mm = this->_internal_focal_length_mm(); + ::uint32_t raw_focal_length_mm; + memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); + if (raw_focal_length_mm != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this->_internal_focal_length_mm(), target); + } + + // float horizontal_sensor_size_mm = 5; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); + ::uint32_t raw_horizontal_sensor_size_mm; + memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); + if (raw_horizontal_sensor_size_mm != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 5, this->_internal_horizontal_sensor_size_mm(), target); + } + + // float vertical_sensor_size_mm = 6; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); + ::uint32_t raw_vertical_sensor_size_mm; + memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); + if (raw_vertical_sensor_size_mm != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 6, this->_internal_vertical_sensor_size_mm(), target); + } + + // uint32 horizontal_resolution_px = 7; + if (this->_internal_horizontal_resolution_px() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 7, this->_internal_horizontal_resolution_px(), target); + } + + // uint32 vertical_resolution_px = 8; + if (this->_internal_vertical_resolution_px() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 8, this->_internal_vertical_resolution_px(), target); + } + + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 9, this->_internal_lens_id(), target); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 10, this->_internal_definition_file_version(), target); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + const std::string& _s = this->_internal_definition_file_uri(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.definition_file_uri"); + target = stream->WriteStringMaybeAliased(11, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.Information) + return target; +} + +::size_t Information::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Information) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string vendor_name = 1; + if (!this->_internal_vendor_name().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_vendor_name()); + } + + // string model_name = 2; + if (!this->_internal_model_name().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_model_name()); + } + + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_firmware_version()); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_definition_file_uri()); + } + + // float focal_length_mm = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_focal_length_mm = this->_internal_focal_length_mm(); + ::uint32_t raw_focal_length_mm; + memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); + if (raw_focal_length_mm != 0) { + total_size += 5; + } + + // float horizontal_sensor_size_mm = 5; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); + ::uint32_t raw_horizontal_sensor_size_mm; + memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); + if (raw_horizontal_sensor_size_mm != 0) { + total_size += 5; + } + + // float vertical_sensor_size_mm = 6; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); + ::uint32_t raw_vertical_sensor_size_mm; + memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); + if (raw_vertical_sensor_size_mm != 0) { + total_size += 5; + } + + // uint32 horizontal_resolution_px = 7; + if (this->_internal_horizontal_resolution_px() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_horizontal_resolution_px()); + } + + // uint32 vertical_resolution_px = 8; + if (this->_internal_vertical_resolution_px() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_vertical_resolution_px()); + } + + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_lens_id()); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_definition_file_version()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Information::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + Information::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Information::GetClassData() const { return &_class_data_; } + + +void Information::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Information) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_vendor_name().empty()) { + _this->_internal_set_vendor_name(from._internal_vendor_name()); + } + if (!from._internal_model_name().empty()) { + _this->_internal_set_model_name(from._internal_model_name()); + } + if (!from._internal_firmware_version().empty()) { + _this->_internal_set_firmware_version(from._internal_firmware_version()); + } + if (!from._internal_definition_file_uri().empty()) { + _this->_internal_set_definition_file_uri(from._internal_definition_file_uri()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_focal_length_mm = from._internal_focal_length_mm(); + ::uint32_t raw_focal_length_mm; + memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); + if (raw_focal_length_mm != 0) { + _this->_internal_set_focal_length_mm(from._internal_focal_length_mm()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_horizontal_sensor_size_mm = from._internal_horizontal_sensor_size_mm(); + ::uint32_t raw_horizontal_sensor_size_mm; + memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); + if (raw_horizontal_sensor_size_mm != 0) { + _this->_internal_set_horizontal_sensor_size_mm(from._internal_horizontal_sensor_size_mm()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_vertical_sensor_size_mm = from._internal_vertical_sensor_size_mm(); + ::uint32_t raw_vertical_sensor_size_mm; + memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); + if (raw_vertical_sensor_size_mm != 0) { + _this->_internal_set_vertical_sensor_size_mm(from._internal_vertical_sensor_size_mm()); + } + if (from._internal_horizontal_resolution_px() != 0) { + _this->_internal_set_horizontal_resolution_px(from._internal_horizontal_resolution_px()); + } + if (from._internal_vertical_resolution_px() != 0) { + _this->_internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); + } + if (from._internal_lens_id() != 0) { + _this->_internal_set_lens_id(from._internal_lens_id()); + } + if (from._internal_definition_file_version() != 0) { + _this->_internal_set_definition_file_version(from._internal_definition_file_version()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Information::CopyFrom(const Information& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Information) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Information::IsInitialized() const { + return true; +} + +void Information::InternalSwap(Information* other) { + using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.vendor_name_, lhs_arena, + &other->_impl_.vendor_name_, rhs_arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.model_name_, lhs_arena, + &other->_impl_.model_name_, rhs_arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.firmware_version_, lhs_arena, + &other->_impl_.firmware_version_, rhs_arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.definition_file_uri_, lhs_arena, + &other->_impl_.definition_file_uri_, rhs_arena); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_version_) + + sizeof(Information::_impl_.definition_file_version_) + - PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_)>( + reinterpret_cast(&_impl_.focal_length_mm_), + reinterpret_cast(&other->_impl_.focal_length_mm_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); +} +// =================================================================== + +class Position::_Internal { + public: +}; + +Position::Position(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Position) +} +Position::Position(const Position& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Position) +} + +inline void Position::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.latitude_deg_) { 0 } + + , decltype(_impl_.longitude_deg_) { 0 } + + , decltype(_impl_.absolute_altitude_m_) { 0 } + + , decltype(_impl_.relative_altitude_m_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +Position::~Position() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Position) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void Position::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void Position::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void Position::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Position) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.latitude_deg_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.relative_altitude_m_) - + reinterpret_cast(&_impl_.latitude_deg_)) + sizeof(_impl_.relative_altitude_m_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Position::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // double latitude_deg = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 9)) { + _impl_.latitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(double); + } else { + goto handle_unusual; + } + continue; + // double longitude_deg = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 17)) { + _impl_.longitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(double); + } else { + goto handle_unusual; + } + continue; + // float absolute_altitude_m = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { + _impl_.absolute_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float relative_altitude_m = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { + _impl_.relative_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* Position::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Position) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // double latitude_deg = 1; + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_latitude_deg = this->_internal_latitude_deg(); + ::uint64_t raw_latitude_deg; + memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); + if (raw_latitude_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteDoubleToArray( + 1, this->_internal_latitude_deg(), target); + } + + // double longitude_deg = 2; + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_longitude_deg = this->_internal_longitude_deg(); + ::uint64_t raw_longitude_deg; + memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); + if (raw_longitude_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteDoubleToArray( + 2, this->_internal_longitude_deg(), target); + } + + // float absolute_altitude_m = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_absolute_altitude_m = this->_internal_absolute_altitude_m(); + ::uint32_t raw_absolute_altitude_m; + memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); + if (raw_absolute_altitude_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_absolute_altitude_m(), target); + } + + // float relative_altitude_m = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_relative_altitude_m = this->_internal_relative_altitude_m(); + ::uint32_t raw_relative_altitude_m; + memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); + if (raw_relative_altitude_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this->_internal_relative_altitude_m(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.Position) + return target; +} + +::size_t Position::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Position) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // double latitude_deg = 1; + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_latitude_deg = this->_internal_latitude_deg(); + ::uint64_t raw_latitude_deg; + memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); + if (raw_latitude_deg != 0) { + total_size += 9; + } + + // double longitude_deg = 2; + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_longitude_deg = this->_internal_longitude_deg(); + ::uint64_t raw_longitude_deg; + memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); + if (raw_longitude_deg != 0) { + total_size += 9; + } + + // float absolute_altitude_m = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_absolute_altitude_m = this->_internal_absolute_altitude_m(); + ::uint32_t raw_absolute_altitude_m; + memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); + if (raw_absolute_altitude_m != 0) { + total_size += 5; + } + + // float relative_altitude_m = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_relative_altitude_m = this->_internal_relative_altitude_m(); + ::uint32_t raw_relative_altitude_m; + memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); + if (raw_relative_altitude_m != 0) { + total_size += 5; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Position::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + Position::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Position::GetClassData() const { return &_class_data_; } + + +void Position::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Position) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_latitude_deg = from._internal_latitude_deg(); + ::uint64_t raw_latitude_deg; + memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); + if (raw_latitude_deg != 0) { + _this->_internal_set_latitude_deg(from._internal_latitude_deg()); + } + static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); + double tmp_longitude_deg = from._internal_longitude_deg(); + ::uint64_t raw_longitude_deg; + memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); + if (raw_longitude_deg != 0) { + _this->_internal_set_longitude_deg(from._internal_longitude_deg()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_absolute_altitude_m = from._internal_absolute_altitude_m(); + ::uint32_t raw_absolute_altitude_m; + memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); + if (raw_absolute_altitude_m != 0) { + _this->_internal_set_absolute_altitude_m(from._internal_absolute_altitude_m()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_relative_altitude_m = from._internal_relative_altitude_m(); + ::uint32_t raw_relative_altitude_m; + memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); + if (raw_relative_altitude_m != 0) { + _this->_internal_set_relative_altitude_m(from._internal_relative_altitude_m()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Position::CopyFrom(const Position& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Position::IsInitialized() const { + return true; +} + +void Position::InternalSwap(Position* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Position, _impl_.relative_altitude_m_) + + sizeof(Position::_impl_.relative_altitude_m_) + - PROTOBUF_FIELD_OFFSET(Position, _impl_.latitude_deg_)>( + reinterpret_cast(&_impl_.latitude_deg_), + reinterpret_cast(&other->_impl_.latitude_deg_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); +} +// =================================================================== + +class Quaternion::_Internal { + public: +}; + +Quaternion::Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Quaternion) +} +Quaternion::Quaternion(const Quaternion& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Quaternion) +} + +inline void Quaternion::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.w_) { 0 } + + , decltype(_impl_.x_) { 0 } + + , decltype(_impl_.y_) { 0 } + + , decltype(_impl_.z_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +Quaternion::~Quaternion() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Quaternion) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void Quaternion::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void Quaternion::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void Quaternion::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Quaternion) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.w_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.z_) - + reinterpret_cast(&_impl_.w_)) + sizeof(_impl_.z_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Quaternion::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // float w = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 13)) { + _impl_.w_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; } continue; - // float horizontal_sensor_size_mm = 5; - case 5: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 45)) { - _impl_.horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + // float x = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 21)) { + _impl_.x_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; } continue; - // float vertical_sensor_size_mm = 6; - case 6: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 53)) { - _impl_.vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + // float y = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { + _impl_.y_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; } continue; - // uint32 horizontal_resolution_px = 7; - case 7: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 56)) { - _impl_.horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - // uint32 vertical_resolution_px = 8; - case 8: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 64)) { - _impl_.vertical_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - // uint32 lens_id = 9; - case 9: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 72)) { - _impl_.lens_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - // uint32 definition_file_version = 10; - case 10: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 80)) { - _impl_.definition_file_version_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); - } else { - goto handle_unusual; - } - continue; - // string definition_file_uri = 11; - case 11: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 90)) { - auto str = _internal_mutable_definition_file_uri(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.definition_file_uri")); + // float z = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { + _impl_.z_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else { goto handle_unusual; } @@ -3730,334 +6171,275 @@ const char* Information::_InternalParse(const char* ptr, ::_pbi::ParseContext* c #undef CHK_ } -::uint8_t* Information::_InternalSerialize( +::uint8_t* Quaternion::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Information) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Quaternion) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // string vendor_name = 1; - if (!this->_internal_vendor_name().empty()) { - const std::string& _s = this->_internal_vendor_name(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.vendor_name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // string model_name = 2; - if (!this->_internal_model_name().empty()) { - const std::string& _s = this->_internal_model_name(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.model_name"); - target = stream->WriteStringMaybeAliased(2, _s, target); - } - - // string firmware_version = 3; - if (!this->_internal_firmware_version().empty()) { - const std::string& _s = this->_internal_firmware_version(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.firmware_version"); - target = stream->WriteStringMaybeAliased(3, _s, target); - } - - // float focal_length_mm = 4; + // float w = 1; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_focal_length_mm = this->_internal_focal_length_mm(); - ::uint32_t raw_focal_length_mm; - memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); - if (raw_focal_length_mm != 0) { + float tmp_w = this->_internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_focal_length_mm(), target); + 1, this->_internal_w(), target); } - // float horizontal_sensor_size_mm = 5; + // float x = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); - ::uint32_t raw_horizontal_sensor_size_mm; - memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); - if (raw_horizontal_sensor_size_mm != 0) { + float tmp_x = this->_internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 5, this->_internal_horizontal_sensor_size_mm(), target); + 2, this->_internal_x(), target); } - // float vertical_sensor_size_mm = 6; + // float y = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); - ::uint32_t raw_vertical_sensor_size_mm; - memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); - if (raw_vertical_sensor_size_mm != 0) { + float tmp_y = this->_internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 6, this->_internal_vertical_sensor_size_mm(), target); - } - - // uint32 horizontal_resolution_px = 7; - if (this->_internal_horizontal_resolution_px() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 7, this->_internal_horizontal_resolution_px(), target); - } - - // uint32 vertical_resolution_px = 8; - if (this->_internal_vertical_resolution_px() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 8, this->_internal_vertical_resolution_px(), target); - } - - // uint32 lens_id = 9; - if (this->_internal_lens_id() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 9, this->_internal_lens_id(), target); + 3, this->_internal_y(), target); } - // uint32 definition_file_version = 10; - if (this->_internal_definition_file_version() != 0) { + // float z = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_z = this->_internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 10, this->_internal_definition_file_version(), target); - } - - // string definition_file_uri = 11; - if (!this->_internal_definition_file_uri().empty()) { - const std::string& _s = this->_internal_definition_file_uri(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.Information.definition_file_uri"); - target = stream->WriteStringMaybeAliased(11, _s, target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this->_internal_z(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.Information) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.Quaternion) return target; } -::size_t Information::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Information) +::size_t Quaternion::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Quaternion) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string vendor_name = 1; - if (!this->_internal_vendor_name().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_vendor_name()); - } - - // string model_name = 2; - if (!this->_internal_model_name().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_model_name()); - } - - // string firmware_version = 3; - if (!this->_internal_firmware_version().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_firmware_version()); - } - - // string definition_file_uri = 11; - if (!this->_internal_definition_file_uri().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_definition_file_uri()); - } - - // float focal_length_mm = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_focal_length_mm = this->_internal_focal_length_mm(); - ::uint32_t raw_focal_length_mm; - memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); - if (raw_focal_length_mm != 0) { - total_size += 5; - } - - // float horizontal_sensor_size_mm = 5; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_horizontal_sensor_size_mm = this->_internal_horizontal_sensor_size_mm(); - ::uint32_t raw_horizontal_sensor_size_mm; - memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); - if (raw_horizontal_sensor_size_mm != 0) { - total_size += 5; - } - - // float vertical_sensor_size_mm = 6; + // float w = 1; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_vertical_sensor_size_mm = this->_internal_vertical_sensor_size_mm(); - ::uint32_t raw_vertical_sensor_size_mm; - memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); - if (raw_vertical_sensor_size_mm != 0) { - total_size += 5; - } - - // uint32 horizontal_resolution_px = 7; - if (this->_internal_horizontal_resolution_px() != 0) { - total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( - this->_internal_horizontal_resolution_px()); + float tmp_w = this->_internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { + total_size += 5; } - // uint32 vertical_resolution_px = 8; - if (this->_internal_vertical_resolution_px() != 0) { - total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( - this->_internal_vertical_resolution_px()); + // float x = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_x = this->_internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { + total_size += 5; } - // uint32 lens_id = 9; - if (this->_internal_lens_id() != 0) { - total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( - this->_internal_lens_id()); + // float y = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_y = this->_internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { + total_size += 5; } - // uint32 definition_file_version = 10; - if (this->_internal_definition_file_version() != 0) { - total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( - this->_internal_definition_file_version()); + // float z = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_z = this->_internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { + total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Information::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Quaternion::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - Information::MergeImpl + Quaternion::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Information::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Quaternion::GetClassData() const { return &_class_data_; } -void Information::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Information) +void Quaternion::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Quaternion) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (!from._internal_vendor_name().empty()) { - _this->_internal_set_vendor_name(from._internal_vendor_name()); - } - if (!from._internal_model_name().empty()) { - _this->_internal_set_model_name(from._internal_model_name()); - } - if (!from._internal_firmware_version().empty()) { - _this->_internal_set_firmware_version(from._internal_firmware_version()); - } - if (!from._internal_definition_file_uri().empty()) { - _this->_internal_set_definition_file_uri(from._internal_definition_file_uri()); - } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_focal_length_mm = from._internal_focal_length_mm(); - ::uint32_t raw_focal_length_mm; - memcpy(&raw_focal_length_mm, &tmp_focal_length_mm, sizeof(tmp_focal_length_mm)); - if (raw_focal_length_mm != 0) { - _this->_internal_set_focal_length_mm(from._internal_focal_length_mm()); + float tmp_w = from._internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { + _this->_internal_set_w(from._internal_w()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_horizontal_sensor_size_mm = from._internal_horizontal_sensor_size_mm(); - ::uint32_t raw_horizontal_sensor_size_mm; - memcpy(&raw_horizontal_sensor_size_mm, &tmp_horizontal_sensor_size_mm, sizeof(tmp_horizontal_sensor_size_mm)); - if (raw_horizontal_sensor_size_mm != 0) { - _this->_internal_set_horizontal_sensor_size_mm(from._internal_horizontal_sensor_size_mm()); + float tmp_x = from._internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { + _this->_internal_set_x(from._internal_x()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_vertical_sensor_size_mm = from._internal_vertical_sensor_size_mm(); - ::uint32_t raw_vertical_sensor_size_mm; - memcpy(&raw_vertical_sensor_size_mm, &tmp_vertical_sensor_size_mm, sizeof(tmp_vertical_sensor_size_mm)); - if (raw_vertical_sensor_size_mm != 0) { - _this->_internal_set_vertical_sensor_size_mm(from._internal_vertical_sensor_size_mm()); - } - if (from._internal_horizontal_resolution_px() != 0) { - _this->_internal_set_horizontal_resolution_px(from._internal_horizontal_resolution_px()); - } - if (from._internal_vertical_resolution_px() != 0) { - _this->_internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); - } - if (from._internal_lens_id() != 0) { - _this->_internal_set_lens_id(from._internal_lens_id()); + float tmp_y = from._internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { + _this->_internal_set_y(from._internal_y()); } - if (from._internal_definition_file_version() != 0) { - _this->_internal_set_definition_file_version(from._internal_definition_file_version()); + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_z = from._internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { + _this->_internal_set_z(from._internal_z()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void Information::CopyFrom(const Information& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Information) +void Quaternion::CopyFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Quaternion) if (&from == this) return; Clear(); MergeFrom(from); } -bool Information::IsInitialized() const { +bool Quaternion::IsInitialized() const { return true; } -void Information::InternalSwap(Information* other) { +void Quaternion::InternalSwap(Quaternion* other) { using std::swap; - auto* lhs_arena = GetArenaForAllocation(); - auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.vendor_name_, lhs_arena, - &other->_impl_.vendor_name_, rhs_arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.model_name_, lhs_arena, - &other->_impl_.model_name_, rhs_arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.firmware_version_, lhs_arena, - &other->_impl_.firmware_version_, rhs_arena); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.definition_file_uri_, lhs_arena, - &other->_impl_.definition_file_uri_, rhs_arena); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(Information, _impl_.definition_file_version_) - + sizeof(Information::_impl_.definition_file_version_) - - PROTOBUF_FIELD_OFFSET(Information, _impl_.focal_length_mm_)>( - reinterpret_cast(&_impl_.focal_length_mm_), - reinterpret_cast(&other->_impl_.focal_length_mm_)); + PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_) + + sizeof(Quaternion::_impl_.z_) + - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)>( + reinterpret_cast(&_impl_.w_), + reinterpret_cast(&other->_impl_.w_)); } -::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); } // =================================================================== -class Position::_Internal { +class CaptureInfo::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::Position& position(const CaptureInfo* msg); + static void set_has_position(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion(const CaptureInfo* msg); + static void set_has_attitude_quaternion(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } }; -Position::Position(::PROTOBUF_NAMESPACE_ID::Arena* arena) +const ::mavsdk::rpc::camera_server::Position& +CaptureInfo::_Internal::position(const CaptureInfo* msg) { + return *msg->_impl_.position_; +} +const ::mavsdk::rpc::camera_server::Quaternion& +CaptureInfo::_Internal::attitude_quaternion(const CaptureInfo* msg) { + return *msg->_impl_.attitude_quaternion_; +} +CaptureInfo::CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Position) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureInfo) } -Position::Position(const Position& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Position) +CaptureInfo::CaptureInfo(const CaptureInfo& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + CaptureInfo* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.file_url_) {} + + , decltype(_impl_.position_){nullptr} + , decltype(_impl_.attitude_quaternion_){nullptr} + , decltype(_impl_.time_utc_us_) {} + + , decltype(_impl_.is_success_) {} + + , decltype(_impl_.index_) {} + }; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.file_url_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.file_url_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_file_url().empty()) { + _this->_impl_.file_url_.Set(from._internal_file_url(), _this->GetArenaForAllocation()); + } + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.position_ = new ::mavsdk::rpc::camera_server::Position(*from._impl_.position_); + } + if ((from._impl_._has_bits_[0] & 0x00000002u) != 0) { + _this->_impl_.attitude_quaternion_ = new ::mavsdk::rpc::camera_server::Quaternion(*from._impl_.attitude_quaternion_); + } + ::memcpy(&_impl_.time_utc_us_, &from._impl_.time_utc_us_, + static_cast<::size_t>(reinterpret_cast(&_impl_.index_) - + reinterpret_cast(&_impl_.time_utc_us_)) + sizeof(_impl_.index_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureInfo) } -inline void Position::SharedCtor(::_pb::Arena* arena) { +inline void CaptureInfo::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.latitude_deg_) { 0 } + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.file_url_) {} - , decltype(_impl_.longitude_deg_) { 0 } + , decltype(_impl_.position_){nullptr} + , decltype(_impl_.attitude_quaternion_){nullptr} + , decltype(_impl_.time_utc_us_) { ::uint64_t{0u} } - , decltype(_impl_.absolute_altitude_m_) { 0 } + , decltype(_impl_.is_success_) { false } - , decltype(_impl_.relative_altitude_m_) { 0 } + , decltype(_impl_.index_) { 0 } - , /*decltype(_impl_._cached_size_)*/{} }; + _impl_.file_url_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.file_url_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -Position::~Position() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Position) +CaptureInfo::~CaptureInfo() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureInfo) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4065,64 +6447,101 @@ Position::~Position() { SharedDtor(); } -inline void Position::SharedDtor() { +inline void CaptureInfo::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.file_url_.Destroy(); + if (this != internal_default_instance()) delete _impl_.position_; + if (this != internal_default_instance()) delete _impl_.attitude_quaternion_; } -void Position::SetCachedSize(int size) const { +void CaptureInfo::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void Position::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Position) +void CaptureInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureInfo) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.latitude_deg_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.relative_altitude_m_) - - reinterpret_cast(&_impl_.latitude_deg_)) + sizeof(_impl_.relative_altitude_m_)); + _impl_.file_url_.ClearToEmpty(); + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.position_ != nullptr); + _impl_.position_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.attitude_quaternion_ != nullptr); + _impl_.attitude_quaternion_->Clear(); + } + } + ::memset(&_impl_.time_utc_us_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.index_) - + reinterpret_cast(&_impl_.time_utc_us_)) + sizeof(_impl_.index_)); + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* Position::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* CaptureInfo::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // double latitude_deg = 1; + // .mavsdk.rpc.camera_server.Position position = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 9)) { - _impl_.latitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(double); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_position(), ptr); + CHK_(ptr); } else { goto handle_unusual; } continue; - // double longitude_deg = 2; + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 17)) { - _impl_.longitude_deg_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(double); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_attitude_quaternion(), ptr); + CHK_(ptr); } else { goto handle_unusual; } continue; - // float absolute_altitude_m = 3; + // uint64 time_utc_us = 3; case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { - _impl_.absolute_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 24)) { + _impl_.time_utc_us_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); } else { goto handle_unusual; } continue; - // float relative_altitude_m = 4; + // bool is_success = 4; case 4: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { - _impl_.relative_altitude_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 32)) { + _impl_.is_success_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // int32 index = 5; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 40)) { + _impl_.index_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // string file_url = 6; + case 6: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 50)) { + auto str = _internal_mutable_file_url(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.CaptureInfo.file_url")); } else { goto handle_unusual; } @@ -4143,6 +6562,7 @@ const char* Position::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -4150,219 +6570,238 @@ const char* Position::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) #undef CHK_ } -::uint8_t* Position::_InternalSerialize( +::uint8_t* CaptureInfo::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Position) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureInfo) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // double latitude_deg = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_latitude_deg = this->_internal_latitude_deg(); - ::uint64_t raw_latitude_deg; - memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); - if (raw_latitude_deg != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 1, this->_internal_latitude_deg(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.Position position = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::position(this), + _Internal::position(this).GetCachedSize(), target, stream); } - // double longitude_deg = 2; - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_longitude_deg = this->_internal_longitude_deg(); - ::uint64_t raw_longitude_deg; - memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); - if (raw_longitude_deg != 0) { + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + if (cached_has_bits & 0x00000002u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(2, _Internal::attitude_quaternion(this), + _Internal::attitude_quaternion(this).GetCachedSize(), target, stream); + } + + // uint64 time_utc_us = 3; + if (this->_internal_time_utc_us() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 2, this->_internal_longitude_deg(), target); + target = ::_pbi::WireFormatLite::WriteUInt64ToArray( + 3, this->_internal_time_utc_us(), target); } - // float absolute_altitude_m = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_absolute_altitude_m = this->_internal_absolute_altitude_m(); - ::uint32_t raw_absolute_altitude_m; - memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); - if (raw_absolute_altitude_m != 0) { + // bool is_success = 4; + if (this->_internal_is_success() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_absolute_altitude_m(), target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 4, this->_internal_is_success(), target); } - // float relative_altitude_m = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_relative_altitude_m = this->_internal_relative_altitude_m(); - ::uint32_t raw_relative_altitude_m; - memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); - if (raw_relative_altitude_m != 0) { + // int32 index = 5; + if (this->_internal_index() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_relative_altitude_m(), target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 5, this->_internal_index(), target); + } + + // string file_url = 6; + if (!this->_internal_file_url().empty()) { + const std::string& _s = this->_internal_file_url(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.CaptureInfo.file_url"); + target = stream->WriteStringMaybeAliased(6, _s, target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.Position) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.CaptureInfo) return target; } -::size_t Position::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Position) +::size_t CaptureInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureInfo) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // double latitude_deg = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_latitude_deg = this->_internal_latitude_deg(); - ::uint64_t raw_latitude_deg; - memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); - if (raw_latitude_deg != 0) { - total_size += 9; + // string file_url = 6; + if (!this->_internal_file_url().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_file_url()); } - // double longitude_deg = 2; - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_longitude_deg = this->_internal_longitude_deg(); - ::uint64_t raw_longitude_deg; - memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); - if (raw_longitude_deg != 0) { - total_size += 9; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + // .mavsdk.rpc.camera_server.Position position = 1; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.position_); + } + + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + if (cached_has_bits & 0x00000002u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.attitude_quaternion_); + } + + } + // uint64 time_utc_us = 3; + if (this->_internal_time_utc_us() != 0) { + total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( + this->_internal_time_utc_us()); } - // float absolute_altitude_m = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_absolute_altitude_m = this->_internal_absolute_altitude_m(); - ::uint32_t raw_absolute_altitude_m; - memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); - if (raw_absolute_altitude_m != 0) { - total_size += 5; + // bool is_success = 4; + if (this->_internal_is_success() != 0) { + total_size += 2; } - // float relative_altitude_m = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_relative_altitude_m = this->_internal_relative_altitude_m(); - ::uint32_t raw_relative_altitude_m; - memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); - if (raw_relative_altitude_m != 0) { - total_size += 5; + // int32 index = 5; + if (this->_internal_index() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_index()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Position::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureInfo::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - Position::MergeImpl + CaptureInfo::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Position::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureInfo::GetClassData() const { return &_class_data_; } -void Position::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Position) +void CaptureInfo::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureInfo) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_latitude_deg = from._internal_latitude_deg(); - ::uint64_t raw_latitude_deg; - memcpy(&raw_latitude_deg, &tmp_latitude_deg, sizeof(tmp_latitude_deg)); - if (raw_latitude_deg != 0) { - _this->_internal_set_latitude_deg(from._internal_latitude_deg()); + if (!from._internal_file_url().empty()) { + _this->_internal_set_file_url(from._internal_file_url()); } - static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); - double tmp_longitude_deg = from._internal_longitude_deg(); - ::uint64_t raw_longitude_deg; - memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); - if (raw_longitude_deg != 0) { - _this->_internal_set_longitude_deg(from._internal_longitude_deg()); + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_position()->::mavsdk::rpc::camera_server::Position::MergeFrom( + from._internal_position()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_attitude_quaternion()->::mavsdk::rpc::camera_server::Quaternion::MergeFrom( + from._internal_attitude_quaternion()); + } } - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_absolute_altitude_m = from._internal_absolute_altitude_m(); - ::uint32_t raw_absolute_altitude_m; - memcpy(&raw_absolute_altitude_m, &tmp_absolute_altitude_m, sizeof(tmp_absolute_altitude_m)); - if (raw_absolute_altitude_m != 0) { - _this->_internal_set_absolute_altitude_m(from._internal_absolute_altitude_m()); + if (from._internal_time_utc_us() != 0) { + _this->_internal_set_time_utc_us(from._internal_time_utc_us()); } - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_relative_altitude_m = from._internal_relative_altitude_m(); - ::uint32_t raw_relative_altitude_m; - memcpy(&raw_relative_altitude_m, &tmp_relative_altitude_m, sizeof(tmp_relative_altitude_m)); - if (raw_relative_altitude_m != 0) { - _this->_internal_set_relative_altitude_m(from._internal_relative_altitude_m()); + if (from._internal_is_success() != 0) { + _this->_internal_set_is_success(from._internal_is_success()); + } + if (from._internal_index() != 0) { + _this->_internal_set_index(from._internal_index()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void Position::CopyFrom(const Position& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Position) +void CaptureInfo::CopyFrom(const CaptureInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureInfo) if (&from == this) return; Clear(); MergeFrom(from); } -bool Position::IsInitialized() const { +bool CaptureInfo::IsInitialized() const { return true; } -void Position::InternalSwap(Position* other) { +void CaptureInfo::InternalSwap(CaptureInfo* other) { using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.file_url_, lhs_arena, + &other->_impl_.file_url_, rhs_arena); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(Position, _impl_.relative_altitude_m_) - + sizeof(Position::_impl_.relative_altitude_m_) - - PROTOBUF_FIELD_OFFSET(Position, _impl_.latitude_deg_)>( - reinterpret_cast(&_impl_.latitude_deg_), - reinterpret_cast(&other->_impl_.latitude_deg_)); + PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_.index_) + + sizeof(CaptureInfo::_impl_.index_) + - PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_.position_)>( + reinterpret_cast(&_impl_.position_), + reinterpret_cast(&other->_impl_.position_)); } -::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); } // =================================================================== -class Quaternion::_Internal { +class CameraServerResult::_Internal { public: }; -Quaternion::Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena) +CameraServerResult::CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CameraServerResult) } -Quaternion::Quaternion(const Quaternion& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Quaternion) +CameraServerResult::CameraServerResult(const CameraServerResult& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + CameraServerResult* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.result_str_) {} + + , decltype(_impl_.result_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.result_str_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.result_str_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_result_str().empty()) { + _this->_impl_.result_str_.Set(from._internal_result_str(), _this->GetArenaForAllocation()); + } + _this->_impl_.result_ = from._impl_.result_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CameraServerResult) } -inline void Quaternion::SharedCtor(::_pb::Arena* arena) { +inline void CameraServerResult::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.w_) { 0 } - - , decltype(_impl_.x_) { 0 } - - , decltype(_impl_.y_) { 0 } + decltype(_impl_.result_str_) {} - , decltype(_impl_.z_) { 0 } + , decltype(_impl_.result_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; + _impl_.result_str_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.result_str_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -Quaternion::~Quaternion() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.Quaternion) +CameraServerResult::~CameraServerResult() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CameraServerResult) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4370,64 +6809,49 @@ Quaternion::~Quaternion() { SharedDtor(); } -inline void Quaternion::SharedDtor() { +inline void CameraServerResult::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.result_str_.Destroy(); } -void Quaternion::SetCachedSize(int size) const { +void CameraServerResult::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void Quaternion::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.Quaternion) +void CameraServerResult::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CameraServerResult) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.w_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.z_) - - reinterpret_cast(&_impl_.w_)) + sizeof(_impl_.z_)); + _impl_.result_str_.ClearToEmpty(); + _impl_.result_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* Quaternion::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* CameraServerResult::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // float w = 1; + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 13)) { - _impl_.w_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_result(static_cast<::mavsdk::rpc::camera_server::CameraServerResult_Result>(val)); } else { goto handle_unusual; } continue; - // float x = 2; + // string result_str = 2; case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 21)) { - _impl_.x_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); - } else { - goto handle_unusual; - } - continue; - // float y = 3; - case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { - _impl_.y_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); - } else { - goto handle_unusual; - } - continue; - // float z = 4; - case 4: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 37)) { - _impl_.z_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + auto str = _internal_mutable_result_str(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.CameraServerResult.result_str")); } else { goto handle_unusual; } @@ -4455,275 +6879,151 @@ const char* Quaternion::_InternalParse(const char* ptr, ::_pbi::ParseContext* ct #undef CHK_ } -::uint8_t* Quaternion::_InternalSerialize( +::uint8_t* CameraServerResult::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CameraServerResult) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // float w = 1; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_w = this->_internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_w(), target); - } - - // float x = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_x = this->_internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_x(), target); - } - - // float y = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_y = this->_internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + if (this->_internal_result() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_y(), target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_result(), target); } - // float z = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_z = this->_internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_z(), target); + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + const std::string& _s = this->_internal_result_str(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.CameraServerResult.result_str"); + target = stream->WriteStringMaybeAliased(2, _s, target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.CameraServerResult) return target; } -::size_t Quaternion::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.Quaternion) +::size_t CameraServerResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CameraServerResult) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float w = 1; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_w = this->_internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - total_size += 5; - } - - // float x = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_x = this->_internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - total_size += 5; - } - - // float y = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_y = this->_internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { - total_size += 5; + // string result_str = 2; + if (!this->_internal_result_str().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_result_str()); } - // float z = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_z = this->_internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - total_size += 5; + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + if (this->_internal_result() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_result()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Quaternion::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CameraServerResult::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - Quaternion::MergeImpl + CameraServerResult::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Quaternion::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CameraServerResult::GetClassData() const { return &_class_data_; } -void Quaternion::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.Quaternion) +void CameraServerResult::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CameraServerResult) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_w = from._internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - _this->_internal_set_w(from._internal_w()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_x = from._internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - _this->_internal_set_x(from._internal_x()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_y = from._internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { - _this->_internal_set_y(from._internal_y()); + if (!from._internal_result_str().empty()) { + _this->_internal_set_result_str(from._internal_result_str()); } - static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_z = from._internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - _this->_internal_set_z(from._internal_z()); + if (from._internal_result() != 0) { + _this->_internal_set_result(from._internal_result()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void Quaternion::CopyFrom(const Quaternion& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.Quaternion) +void CameraServerResult::CopyFrom(const CameraServerResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CameraServerResult) if (&from == this) return; Clear(); MergeFrom(from); } -bool Quaternion::IsInitialized() const { +bool CameraServerResult::IsInitialized() const { return true; } -void Quaternion::InternalSwap(Quaternion* other) { +void CameraServerResult::InternalSwap(CameraServerResult* other) { using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_) - + sizeof(Quaternion::_impl_.z_) - - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)>( - reinterpret_cast(&_impl_.w_), - reinterpret_cast(&other->_impl_.w_)); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.result_str_, lhs_arena, + &other->_impl_.result_str_, rhs_arena); + swap(_impl_.result_, other->_impl_.result_); } -::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); } // =================================================================== -class CaptureInfo::_Internal { +class StorageInformation::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::Position& position(const CaptureInfo* msg); - static void set_has_position(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } - static const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion(const CaptureInfo* msg); - static void set_has_attitude_quaternion(HasBits* has_bits) { - (*has_bits)[0] |= 2u; - } }; -const ::mavsdk::rpc::camera_server::Position& -CaptureInfo::_Internal::position(const CaptureInfo* msg) { - return *msg->_impl_.position_; -} -const ::mavsdk::rpc::camera_server::Quaternion& -CaptureInfo::_Internal::attitude_quaternion(const CaptureInfo* msg) { - return *msg->_impl_.attitude_quaternion_; -} -CaptureInfo::CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena) +StorageInformation::StorageInformation(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureInfo) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StorageInformation) +} +StorageInformation::StorageInformation(const StorageInformation& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StorageInformation) } -CaptureInfo::CaptureInfo(const CaptureInfo& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - CaptureInfo* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.file_url_) {} - , decltype(_impl_.position_){nullptr} - , decltype(_impl_.attitude_quaternion_){nullptr} - , decltype(_impl_.time_utc_us_) {} +inline void StorageInformation::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.used_storage_mib_) { 0 } - , decltype(_impl_.is_success_) {} + , decltype(_impl_.available_storage_mib_) { 0 } - , decltype(_impl_.index_) {} - }; + , decltype(_impl_.total_storage_mib_) { 0 } - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.file_url_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.file_url_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_file_url().empty()) { - _this->_impl_.file_url_.Set(from._internal_file_url(), _this->GetArenaForAllocation()); - } - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.position_ = new ::mavsdk::rpc::camera_server::Position(*from._impl_.position_); - } - if ((from._impl_._has_bits_[0] & 0x00000002u) != 0) { - _this->_impl_.attitude_quaternion_ = new ::mavsdk::rpc::camera_server::Quaternion(*from._impl_.attitude_quaternion_); - } - ::memcpy(&_impl_.time_utc_us_, &from._impl_.time_utc_us_, - static_cast<::size_t>(reinterpret_cast(&_impl_.index_) - - reinterpret_cast(&_impl_.time_utc_us_)) + sizeof(_impl_.index_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureInfo) -} + , decltype(_impl_.storage_status_) { 0 } -inline void CaptureInfo::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.file_url_) {} + , decltype(_impl_.storage_id_) { 0u } - , decltype(_impl_.position_){nullptr} - , decltype(_impl_.attitude_quaternion_){nullptr} - , decltype(_impl_.time_utc_us_) { ::uint64_t{0u} } + , decltype(_impl_.storage_type_) { 0 } - , decltype(_impl_.is_success_) { false } + , decltype(_impl_.read_speed_) { 0 } - , decltype(_impl_.index_) { 0 } + , decltype(_impl_.write_speed_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} }; - _impl_.file_url_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.file_url_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -CaptureInfo::~CaptureInfo() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureInfo) +StorageInformation::~StorageInformation() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StorageInformation) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4731,101 +7031,102 @@ CaptureInfo::~CaptureInfo() { SharedDtor(); } -inline void CaptureInfo::SharedDtor() { +inline void StorageInformation::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.file_url_.Destroy(); - if (this != internal_default_instance()) delete _impl_.position_; - if (this != internal_default_instance()) delete _impl_.attitude_quaternion_; } -void CaptureInfo::SetCachedSize(int size) const { +void StorageInformation::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void CaptureInfo::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureInfo) +void StorageInformation::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StorageInformation) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.file_url_.ClearToEmpty(); - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000003u) { - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.position_ != nullptr); - _impl_.position_->Clear(); - } - if (cached_has_bits & 0x00000002u) { - ABSL_DCHECK(_impl_.attitude_quaternion_ != nullptr); - _impl_.attitude_quaternion_->Clear(); - } - } - ::memset(&_impl_.time_utc_us_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.index_) - - reinterpret_cast(&_impl_.time_utc_us_)) + sizeof(_impl_.index_)); - _impl_._has_bits_.Clear(); + ::memset(&_impl_.used_storage_mib_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.write_speed_) - + reinterpret_cast(&_impl_.used_storage_mib_)) + sizeof(_impl_.write_speed_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* CaptureInfo::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* StorageInformation::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.Position position = 1; + // float used_storage_mib = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_position(), ptr); - CHK_(ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 13)) { + _impl_.used_storage_mib_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else { goto handle_unusual; } continue; - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + // float available_storage_mib = 2; case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - ptr = ctx->ParseMessage(_internal_mutable_attitude_quaternion(), ptr); - CHK_(ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 21)) { + _impl_.available_storage_mib_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else { goto handle_unusual; } continue; - // uint64 time_utc_us = 3; + // float total_storage_mib = 3; case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 24)) { - _impl_.time_utc_us_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); - CHK_(ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { + _impl_.total_storage_mib_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else { goto handle_unusual; } continue; - // bool is_success = 4; + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; case 4: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 32)) { - _impl_.is_success_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); + _internal_set_storage_status(static_cast<::mavsdk::rpc::camera_server::StorageInformation_StorageStatus>(val)); } else { goto handle_unusual; } continue; - // int32 index = 5; + // uint32 storage_id = 5; case 5: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 40)) { - _impl_.index_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else { goto handle_unusual; } continue; - // string file_url = 6; + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; case 6: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 50)) { - auto str = _internal_mutable_file_url(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 48)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.CaptureInfo.file_url")); + _internal_set_storage_type(static_cast<::mavsdk::rpc::camera_server::StorageInformation_StorageType>(val)); + } else { + goto handle_unusual; + } + continue; + // float read_speed = 7; + case 7: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 61)) { + _impl_.read_speed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float write_speed = 8; + case 8: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 69)) { + _impl_.write_speed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else { goto handle_unusual; } @@ -4846,7 +7147,6 @@ const char* CaptureInfo::_InternalParse(const char* ptr, ::_pbi::ParseContext* c CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -4854,238 +7154,298 @@ const char* CaptureInfo::_InternalParse(const char* ptr, ::_pbi::ParseContext* c #undef CHK_ } -::uint8_t* CaptureInfo::_InternalSerialize( +::uint8_t* StorageInformation::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureInfo) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StorageInformation) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.Position position = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::position(this), - _Internal::position(this).GetCachedSize(), target, stream); + // float used_storage_mib = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_used_storage_mib = this->_internal_used_storage_mib(); + ::uint32_t raw_used_storage_mib; + memcpy(&raw_used_storage_mib, &tmp_used_storage_mib, sizeof(tmp_used_storage_mib)); + if (raw_used_storage_mib != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_used_storage_mib(), target); } - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; - if (cached_has_bits & 0x00000002u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(2, _Internal::attitude_quaternion(this), - _Internal::attitude_quaternion(this).GetCachedSize(), target, stream); + // float available_storage_mib = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_storage_mib = this->_internal_available_storage_mib(); + ::uint32_t raw_available_storage_mib; + memcpy(&raw_available_storage_mib, &tmp_available_storage_mib, sizeof(tmp_available_storage_mib)); + if (raw_available_storage_mib != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_available_storage_mib(), target); } - // uint64 time_utc_us = 3; - if (this->_internal_time_utc_us() != 0) { + // float total_storage_mib = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_total_storage_mib = this->_internal_total_storage_mib(); + ::uint32_t raw_total_storage_mib; + memcpy(&raw_total_storage_mib, &tmp_total_storage_mib, sizeof(tmp_total_storage_mib)); + if (raw_total_storage_mib != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt64ToArray( - 3, this->_internal_time_utc_us(), target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_total_storage_mib(), target); } - // bool is_success = 4; - if (this->_internal_is_success() != 0) { + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; + if (this->_internal_storage_status() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteBoolToArray( - 4, this->_internal_is_success(), target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 4, this->_internal_storage_status(), target); } - // int32 index = 5; - if (this->_internal_index() != 0) { + // uint32 storage_id = 5; + if (this->_internal_storage_id() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 5, this->_internal_index(), target); + target = ::_pbi::WireFormatLite::WriteUInt32ToArray( + 5, this->_internal_storage_id(), target); } - // string file_url = 6; - if (!this->_internal_file_url().empty()) { - const std::string& _s = this->_internal_file_url(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.CaptureInfo.file_url"); - target = stream->WriteStringMaybeAliased(6, _s, target); + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; + if (this->_internal_storage_type() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 6, this->_internal_storage_type(), target); + } + + // float read_speed = 7; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_read_speed = this->_internal_read_speed(); + ::uint32_t raw_read_speed; + memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); + if (raw_read_speed != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 7, this->_internal_read_speed(), target); + } + + // float write_speed = 8; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_write_speed = this->_internal_write_speed(); + ::uint32_t raw_write_speed; + memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); + if (raw_write_speed != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 8, this->_internal_write_speed(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.CaptureInfo) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.StorageInformation) return target; } -::size_t CaptureInfo::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureInfo) +::size_t StorageInformation::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StorageInformation) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string file_url = 6; - if (!this->_internal_file_url().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_file_url()); + // float used_storage_mib = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_used_storage_mib = this->_internal_used_storage_mib(); + ::uint32_t raw_used_storage_mib; + memcpy(&raw_used_storage_mib, &tmp_used_storage_mib, sizeof(tmp_used_storage_mib)); + if (raw_used_storage_mib != 0) { + total_size += 5; } - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000003u) { - // .mavsdk.rpc.camera_server.Position position = 1; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.position_); - } + // float available_storage_mib = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_storage_mib = this->_internal_available_storage_mib(); + ::uint32_t raw_available_storage_mib; + memcpy(&raw_available_storage_mib, &tmp_available_storage_mib, sizeof(tmp_available_storage_mib)); + if (raw_available_storage_mib != 0) { + total_size += 5; + } - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; - if (cached_has_bits & 0x00000002u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.attitude_quaternion_); - } + // float total_storage_mib = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_total_storage_mib = this->_internal_total_storage_mib(); + ::uint32_t raw_total_storage_mib; + memcpy(&raw_total_storage_mib, &tmp_total_storage_mib, sizeof(tmp_total_storage_mib)); + if (raw_total_storage_mib != 0) { + total_size += 5; + } + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; + if (this->_internal_storage_status() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_status()); } - // uint64 time_utc_us = 3; - if (this->_internal_time_utc_us() != 0) { - total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( - this->_internal_time_utc_us()); + + // uint32 storage_id = 5; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( + this->_internal_storage_id()); } - // bool is_success = 4; - if (this->_internal_is_success() != 0) { - total_size += 2; + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; + if (this->_internal_storage_type() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_type()); } - // int32 index = 5; - if (this->_internal_index() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_index()); + // float read_speed = 7; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_read_speed = this->_internal_read_speed(); + ::uint32_t raw_read_speed; + memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); + if (raw_read_speed != 0) { + total_size += 5; + } + + // float write_speed = 8; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_write_speed = this->_internal_write_speed(); + ::uint32_t raw_write_speed; + memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); + if (raw_write_speed != 0) { + total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureInfo::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StorageInformation::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - CaptureInfo::MergeImpl + StorageInformation::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureInfo::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StorageInformation::GetClassData() const { return &_class_data_; } -void CaptureInfo::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureInfo) +void StorageInformation::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StorageInformation) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (!from._internal_file_url().empty()) { - _this->_internal_set_file_url(from._internal_file_url()); + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_used_storage_mib = from._internal_used_storage_mib(); + ::uint32_t raw_used_storage_mib; + memcpy(&raw_used_storage_mib, &tmp_used_storage_mib, sizeof(tmp_used_storage_mib)); + if (raw_used_storage_mib != 0) { + _this->_internal_set_used_storage_mib(from._internal_used_storage_mib()); } - cached_has_bits = from._impl_._has_bits_[0]; - if (cached_has_bits & 0x00000003u) { - if (cached_has_bits & 0x00000001u) { - _this->_internal_mutable_position()->::mavsdk::rpc::camera_server::Position::MergeFrom( - from._internal_position()); - } - if (cached_has_bits & 0x00000002u) { - _this->_internal_mutable_attitude_quaternion()->::mavsdk::rpc::camera_server::Quaternion::MergeFrom( - from._internal_attitude_quaternion()); - } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_storage_mib = from._internal_available_storage_mib(); + ::uint32_t raw_available_storage_mib; + memcpy(&raw_available_storage_mib, &tmp_available_storage_mib, sizeof(tmp_available_storage_mib)); + if (raw_available_storage_mib != 0) { + _this->_internal_set_available_storage_mib(from._internal_available_storage_mib()); } - if (from._internal_time_utc_us() != 0) { - _this->_internal_set_time_utc_us(from._internal_time_utc_us()); + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_total_storage_mib = from._internal_total_storage_mib(); + ::uint32_t raw_total_storage_mib; + memcpy(&raw_total_storage_mib, &tmp_total_storage_mib, sizeof(tmp_total_storage_mib)); + if (raw_total_storage_mib != 0) { + _this->_internal_set_total_storage_mib(from._internal_total_storage_mib()); } - if (from._internal_is_success() != 0) { - _this->_internal_set_is_success(from._internal_is_success()); + if (from._internal_storage_status() != 0) { + _this->_internal_set_storage_status(from._internal_storage_status()); } - if (from._internal_index() != 0) { - _this->_internal_set_index(from._internal_index()); + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); + } + if (from._internal_storage_type() != 0) { + _this->_internal_set_storage_type(from._internal_storage_type()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_read_speed = from._internal_read_speed(); + ::uint32_t raw_read_speed; + memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); + if (raw_read_speed != 0) { + _this->_internal_set_read_speed(from._internal_read_speed()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_write_speed = from._internal_write_speed(); + ::uint32_t raw_write_speed; + memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); + if (raw_write_speed != 0) { + _this->_internal_set_write_speed(from._internal_write_speed()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void CaptureInfo::CopyFrom(const CaptureInfo& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureInfo) +void StorageInformation::CopyFrom(const StorageInformation& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StorageInformation) if (&from == this) return; Clear(); MergeFrom(from); } -bool CaptureInfo::IsInitialized() const { +bool StorageInformation::IsInitialized() const { return true; } -void CaptureInfo::InternalSwap(CaptureInfo* other) { +void StorageInformation::InternalSwap(StorageInformation* other) { using std::swap; - auto* lhs_arena = GetArenaForAllocation(); - auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.file_url_, lhs_arena, - &other->_impl_.file_url_, rhs_arena); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_.index_) - + sizeof(CaptureInfo::_impl_.index_) - - PROTOBUF_FIELD_OFFSET(CaptureInfo, _impl_.position_)>( - reinterpret_cast(&_impl_.position_), - reinterpret_cast(&other->_impl_.position_)); + PROTOBUF_FIELD_OFFSET(StorageInformation, _impl_.write_speed_) + + sizeof(StorageInformation::_impl_.write_speed_) + - PROTOBUF_FIELD_OFFSET(StorageInformation, _impl_.used_storage_mib_)>( + reinterpret_cast(&_impl_.used_storage_mib_), + reinterpret_cast(&other->_impl_.used_storage_mib_)); } -::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata StorageInformation::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); } // =================================================================== -class CameraServerResult::_Internal { +class CaptureStatus::_Internal { public: }; -CameraServerResult::CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena) +CaptureStatus::CaptureStatus(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CameraServerResult) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureStatus) } -CameraServerResult::CameraServerResult(const CameraServerResult& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - CameraServerResult* const _this = this; (void)_this; +CaptureStatus::CaptureStatus(const CaptureStatus& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureStatus) +} + +inline void CaptureStatus::SharedCtor(::_pb::Arena* arena) { + (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.result_str_) {} + decltype(_impl_.image_interval_) { 0 } - , decltype(_impl_.result_) {} + , decltype(_impl_.recording_time_s_) { 0 } - , /*decltype(_impl_._cached_size_)*/{}}; + , decltype(_impl_.available_capacity_) { 0 } - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.result_str_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.result_str_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_result_str().empty()) { - _this->_impl_.result_str_.Set(from._internal_result_str(), _this->GetArenaForAllocation()); - } - _this->_impl_.result_ = from._impl_.result_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CameraServerResult) -} + , decltype(_impl_.image_status_) { 0 } -inline void CameraServerResult::SharedCtor(::_pb::Arena* arena) { - (void)arena; - new (&_impl_) Impl_{ - decltype(_impl_.result_str_) {} + , decltype(_impl_.video_status_) { 0 } - , decltype(_impl_.result_) { 0 } + , decltype(_impl_.image_count_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; - _impl_.result_str_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.result_str_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -CameraServerResult::~CameraServerResult() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CameraServerResult) +CaptureStatus::~CaptureStatus() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureStatus) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -5093,49 +7453,84 @@ CameraServerResult::~CameraServerResult() { SharedDtor(); } -inline void CameraServerResult::SharedDtor() { +inline void CaptureStatus::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.result_str_.Destroy(); } -void CameraServerResult::SetCachedSize(int size) const { +void CaptureStatus::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void CameraServerResult::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CameraServerResult) +void CaptureStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureStatus) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.result_str_.ClearToEmpty(); - _impl_.result_ = 0; + ::memset(&_impl_.image_interval_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.image_count_) - + reinterpret_cast(&_impl_.image_interval_)) + sizeof(_impl_.image_count_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* CameraServerResult::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* CaptureStatus::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + // float image_interval = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 13)) { + _impl_.image_interval_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float recording_time_s = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 21)) { + _impl_.recording_time_s_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // float available_capacity = 3; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { + _impl_.available_capacity_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else { + goto handle_unusual; + } + continue; + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 32)) { ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); - _internal_set_result(static_cast<::mavsdk::rpc::camera_server::CameraServerResult_Result>(val)); + _internal_set_image_status(static_cast<::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus>(val)); } else { goto handle_unusual; } continue; - // string result_str = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - auto str = _internal_mutable_result_str(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 40)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_video_status(static_cast<::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus>(val)); + } else { + goto handle_unusual; + } + continue; + // int32 image_count = 6; + case 6: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 48)) { + _impl_.image_count_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.CameraServerResult.result_str")); } else { goto handle_unusual; } @@ -5163,107 +7558,204 @@ const char* CameraServerResult::_InternalParse(const char* ptr, ::_pbi::ParseCon #undef CHK_ } -::uint8_t* CameraServerResult::_InternalSerialize( +::uint8_t* CaptureStatus::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CameraServerResult) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureStatus) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; - if (this->_internal_result() != 0) { + // float image_interval = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_image_interval = this->_internal_image_interval(); + ::uint32_t raw_image_interval; + memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); + if (raw_image_interval != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_image_interval(), target); + } + + // float recording_time_s = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_recording_time_s = this->_internal_recording_time_s(); + ::uint32_t raw_recording_time_s; + memcpy(&raw_recording_time_s, &tmp_recording_time_s, sizeof(tmp_recording_time_s)); + if (raw_recording_time_s != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_recording_time_s(), target); + } + + // float available_capacity = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_capacity = this->_internal_available_capacity(); + ::uint32_t raw_available_capacity; + memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); + if (raw_available_capacity != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_available_capacity(), target); + } + + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + if (this->_internal_image_status() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_result(), target); + 4, this->_internal_image_status(), target); } - // string result_str = 2; - if (!this->_internal_result_str().empty()) { - const std::string& _s = this->_internal_result_str(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.CameraServerResult.result_str"); - target = stream->WriteStringMaybeAliased(2, _s, target); + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + if (this->_internal_video_status() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 5, this->_internal_video_status(), target); + } + + // int32 image_count = 6; + if (this->_internal_image_count() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 6, this->_internal_image_count(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.CameraServerResult) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.CaptureStatus) return target; } -::size_t CameraServerResult::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CameraServerResult) +::size_t CaptureStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureStatus) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string result_str = 2; - if (!this->_internal_result_str().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_result_str()); + // float image_interval = 1; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_image_interval = this->_internal_image_interval(); + ::uint32_t raw_image_interval; + memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); + if (raw_image_interval != 0) { + total_size += 5; } - // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; - if (this->_internal_result() != 0) { + // float recording_time_s = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_recording_time_s = this->_internal_recording_time_s(); + ::uint32_t raw_recording_time_s; + memcpy(&raw_recording_time_s, &tmp_recording_time_s, sizeof(tmp_recording_time_s)); + if (raw_recording_time_s != 0) { + total_size += 5; + } + + // float available_capacity = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_capacity = this->_internal_available_capacity(); + ::uint32_t raw_available_capacity; + memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); + if (raw_available_capacity != 0) { + total_size += 5; + } + + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + if (this->_internal_image_status() != 0) { total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_result()); + ::_pbi::WireFormatLite::EnumSize(this->_internal_image_status()); + } + + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + if (this->_internal_video_status() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_video_status()); + } + + // int32 image_count = 6; + if (this->_internal_image_count() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_image_count()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CameraServerResult::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureStatus::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - CameraServerResult::MergeImpl + CaptureStatus::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CameraServerResult::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureStatus::GetClassData() const { return &_class_data_; } -void CameraServerResult::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CameraServerResult) +void CaptureStatus::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureStatus) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (!from._internal_result_str().empty()) { - _this->_internal_set_result_str(from._internal_result_str()); + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_image_interval = from._internal_image_interval(); + ::uint32_t raw_image_interval; + memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); + if (raw_image_interval != 0) { + _this->_internal_set_image_interval(from._internal_image_interval()); } - if (from._internal_result() != 0) { - _this->_internal_set_result(from._internal_result()); + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_recording_time_s = from._internal_recording_time_s(); + ::uint32_t raw_recording_time_s; + memcpy(&raw_recording_time_s, &tmp_recording_time_s, sizeof(tmp_recording_time_s)); + if (raw_recording_time_s != 0) { + _this->_internal_set_recording_time_s(from._internal_recording_time_s()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); + float tmp_available_capacity = from._internal_available_capacity(); + ::uint32_t raw_available_capacity; + memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); + if (raw_available_capacity != 0) { + _this->_internal_set_available_capacity(from._internal_available_capacity()); + } + if (from._internal_image_status() != 0) { + _this->_internal_set_image_status(from._internal_image_status()); + } + if (from._internal_video_status() != 0) { + _this->_internal_set_video_status(from._internal_video_status()); + } + if (from._internal_image_count() != 0) { + _this->_internal_set_image_count(from._internal_image_count()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void CameraServerResult::CopyFrom(const CameraServerResult& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CameraServerResult) +void CaptureStatus::CopyFrom(const CaptureStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureStatus) if (&from == this) return; Clear(); MergeFrom(from); } -bool CameraServerResult::IsInitialized() const { +bool CaptureStatus::IsInitialized() const { return true; } -void CameraServerResult::InternalSwap(CameraServerResult* other) { +void CaptureStatus::InternalSwap(CaptureStatus* other) { using std::swap; - auto* lhs_arena = GetArenaForAllocation(); - auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.result_str_, lhs_arena, - &other->_impl_.result_str_, rhs_arena); - swap(_impl_.result_, other->_impl_.result_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(CaptureStatus, _impl_.image_count_) + + sizeof(CaptureStatus::_impl_.image_count_) + - PROTOBUF_FIELD_OFFSET(CaptureStatus, _impl_.image_interval_)>( + reinterpret_cast(&_impl_.image_interval_), + reinterpret_cast(&other->_impl_.image_interval_)); } -::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -5334,6 +7826,38 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetModeResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetModeResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetModeResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StorageInformationResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StorageInformationResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StorageInformationResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::CaptureStatusResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::CaptureStatusResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::CaptureStatusResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); @@ -5362,6 +7886,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::CameraServerResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::CameraServerResult >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::CameraServerResult >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StorageInformation* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StorageInformation >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StorageInformation >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::CaptureStatus* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::CaptureStatus >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::CaptureStatus >(arena); +} PROTOBUF_NAMESPACE_CLOSE // @@protoc_insertion_point(global_scope) #include "google/protobuf/port_undef.inc" diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index be42de2c4a..6d51d6c038 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -62,6 +62,12 @@ extern CameraServerResultDefaultTypeInternal _CameraServerResult_default_instanc class CaptureInfo; struct CaptureInfoDefaultTypeInternal; extern CaptureInfoDefaultTypeInternal _CaptureInfo_default_instance_; +class CaptureStatus; +struct CaptureStatusDefaultTypeInternal; +extern CaptureStatusDefaultTypeInternal _CaptureStatus_default_instance_; +class CaptureStatusResponse; +struct CaptureStatusResponseDefaultTypeInternal; +extern CaptureStatusResponseDefaultTypeInternal _CaptureStatusResponse_default_instance_; class Information; struct InformationDefaultTypeInternal; extern InformationDefaultTypeInternal _Information_default_instance_; @@ -71,6 +77,18 @@ extern PositionDefaultTypeInternal _Position_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +class RespondCaptureStatusRequest; +struct RespondCaptureStatusRequestDefaultTypeInternal; +extern RespondCaptureStatusRequestDefaultTypeInternal _RespondCaptureStatusRequest_default_instance_; +class RespondCaptureStatusResponse; +struct RespondCaptureStatusResponseDefaultTypeInternal; +extern RespondCaptureStatusResponseDefaultTypeInternal _RespondCaptureStatusResponse_default_instance_; +class RespondStorageInformationRequest; +struct RespondStorageInformationRequestDefaultTypeInternal; +extern RespondStorageInformationRequestDefaultTypeInternal _RespondStorageInformationRequest_default_instance_; +class RespondStorageInformationResponse; +struct RespondStorageInformationResponseDefaultTypeInternal; +extern RespondStorageInformationResponseDefaultTypeInternal _RespondStorageInformationResponse_default_instance_; class RespondTakePhotoRequest; struct RespondTakePhotoRequestDefaultTypeInternal; extern RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_default_instance_; @@ -104,6 +122,15 @@ extern StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_ class StopVideoStreamingResponse; struct StopVideoStreamingResponseDefaultTypeInternal; extern StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; +class StorageInformation; +struct StorageInformationDefaultTypeInternal; +extern StorageInformationDefaultTypeInternal _StorageInformation_default_instance_; +class StorageInformationResponse; +struct StorageInformationResponseDefaultTypeInternal; +extern StorageInformationResponseDefaultTypeInternal _StorageInformationResponse_default_instance_; +class SubscribeCaptureStatusRequest; +struct SubscribeCaptureStatusRequestDefaultTypeInternal; +extern SubscribeCaptureStatusRequestDefaultTypeInternal _SubscribeCaptureStatusRequest_default_instance_; class SubscribeSetModeRequest; struct SubscribeSetModeRequestDefaultTypeInternal; extern SubscribeSetModeRequestDefaultTypeInternal _SubscribeSetModeRequest_default_instance_; @@ -119,6 +146,9 @@ extern SubscribeStopVideoRequestDefaultTypeInternal _SubscribeStopVideoRequest_d class SubscribeStopVideoStreamingRequest; struct SubscribeStopVideoStreamingRequestDefaultTypeInternal; extern SubscribeStopVideoStreamingRequestDefaultTypeInternal _SubscribeStopVideoStreamingRequest_default_instance_; +class SubscribeStorageInformationRequest; +struct SubscribeStorageInformationRequestDefaultTypeInternal; +extern SubscribeStorageInformationRequestDefaultTypeInternal _SubscribeStorageInformationRequest_default_instance_; class SubscribeTakePhotoRequest; struct SubscribeTakePhotoRequestDefaultTypeInternal; extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_default_instance_; @@ -134,12 +164,24 @@ ::mavsdk::rpc::camera_server::CameraServerResult* Arena::CreateMaybeMessage<::ma template <> ::mavsdk::rpc::camera_server::CaptureInfo* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(Arena*); template <> +::mavsdk::rpc::camera_server::CaptureStatus* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatus>(Arena*); +template <> +::mavsdk::rpc::camera_server::CaptureStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatusResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(Arena*); template <> ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Position>(Arena*); template <> ::mavsdk::rpc::camera_server::Quaternion* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Quaternion>(Arena*); template <> +::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondCaptureStatusRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStorageInformationRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStorageInformationRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStorageInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStorageInformationResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondTakePhotoResponse>(Arena*); @@ -162,6 +204,12 @@ ::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage<::mav template <> ::mavsdk::rpc::camera_server::StopVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StopVideoStreamingResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::StorageInformation* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StorageInformation>(Arena*); +template <> +::mavsdk::rpc::camera_server::StorageInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StorageInformationResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeSetModeRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); @@ -172,6 +220,8 @@ ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* Arena::CreateMaybeMessa template <> ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest>(Arena*); template <> +::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); @@ -219,6 +269,136 @@ inline bool CameraServerResult_Result_Parse(absl::string_view name, CameraServer return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( CameraServerResult_Result_descriptor(), name, value); } +enum StorageInformation_StorageStatus : int { + StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE = 0, + StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED = 1, + StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED = 2, + StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED = 3, + StorageInformation_StorageStatus_StorageInformation_StorageStatus_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + StorageInformation_StorageStatus_StorageInformation_StorageStatus_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool StorageInformation_StorageStatus_IsValid(int value); +constexpr StorageInformation_StorageStatus StorageInformation_StorageStatus_StorageStatus_MIN = static_cast(0); +constexpr StorageInformation_StorageStatus StorageInformation_StorageStatus_StorageStatus_MAX = static_cast(3); +constexpr int StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE = 3 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +StorageInformation_StorageStatus_descriptor(); +template +const std::string& StorageInformation_StorageStatus_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to StorageStatus_Name()."); + return StorageInformation_StorageStatus_Name(static_cast(value)); +} +template <> +inline const std::string& StorageInformation_StorageStatus_Name(StorageInformation_StorageStatus value) { + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool StorageInformation_StorageStatus_Parse(absl::string_view name, StorageInformation_StorageStatus* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + StorageInformation_StorageStatus_descriptor(), name, value); +} +enum StorageInformation_StorageType : int { + StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN = 0, + StorageInformation_StorageType_STORAGE_TYPE_USB_STICK = 1, + StorageInformation_StorageType_STORAGE_TYPE_SD = 2, + StorageInformation_StorageType_STORAGE_TYPE_MICROSD = 3, + StorageInformation_StorageType_STORAGE_TYPE_HD = 7, + StorageInformation_StorageType_STORAGE_TYPE_OTHER = 254, + StorageInformation_StorageType_StorageInformation_StorageType_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + StorageInformation_StorageType_StorageInformation_StorageType_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool StorageInformation_StorageType_IsValid(int value); +constexpr StorageInformation_StorageType StorageInformation_StorageType_StorageType_MIN = static_cast(0); +constexpr StorageInformation_StorageType StorageInformation_StorageType_StorageType_MAX = static_cast(254); +constexpr int StorageInformation_StorageType_StorageType_ARRAYSIZE = 254 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +StorageInformation_StorageType_descriptor(); +template +const std::string& StorageInformation_StorageType_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to StorageType_Name()."); + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum(StorageInformation_StorageType_descriptor(), value); +} +inline bool StorageInformation_StorageType_Parse(absl::string_view name, StorageInformation_StorageType* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + StorageInformation_StorageType_descriptor(), name, value); +} +enum CaptureStatus_ImageStatus : int { + CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE = 0, + CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS = 1, + CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE = 2, + CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS = 3, + CaptureStatus_ImageStatus_CaptureStatus_ImageStatus_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + CaptureStatus_ImageStatus_CaptureStatus_ImageStatus_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool CaptureStatus_ImageStatus_IsValid(int value); +constexpr CaptureStatus_ImageStatus CaptureStatus_ImageStatus_ImageStatus_MIN = static_cast(0); +constexpr CaptureStatus_ImageStatus CaptureStatus_ImageStatus_ImageStatus_MAX = static_cast(3); +constexpr int CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE = 3 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +CaptureStatus_ImageStatus_descriptor(); +template +const std::string& CaptureStatus_ImageStatus_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to ImageStatus_Name()."); + return CaptureStatus_ImageStatus_Name(static_cast(value)); +} +template <> +inline const std::string& CaptureStatus_ImageStatus_Name(CaptureStatus_ImageStatus value) { + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool CaptureStatus_ImageStatus_Parse(absl::string_view name, CaptureStatus_ImageStatus* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + CaptureStatus_ImageStatus_descriptor(), name, value); +} +enum CaptureStatus_VideoStatus : int { + CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE = 0, + CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS = 1, + CaptureStatus_VideoStatus_CaptureStatus_VideoStatus_INT_MIN_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::min(), + CaptureStatus_VideoStatus_CaptureStatus_VideoStatus_INT_MAX_SENTINEL_DO_NOT_USE_ = + std::numeric_limits<::int32_t>::max(), +}; + +bool CaptureStatus_VideoStatus_IsValid(int value); +constexpr CaptureStatus_VideoStatus CaptureStatus_VideoStatus_VideoStatus_MIN = static_cast(0); +constexpr CaptureStatus_VideoStatus CaptureStatus_VideoStatus_VideoStatus_MAX = static_cast(1); +constexpr int CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE = 1 + 1; +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* +CaptureStatus_VideoStatus_descriptor(); +template +const std::string& CaptureStatus_VideoStatus_Name(T value) { + static_assert(std::is_same::value || + std::is_integral::value, + "Incorrect type passed to VideoStatus_Name()."); + return CaptureStatus_VideoStatus_Name(static_cast(value)); +} +template <> +inline const std::string& CaptureStatus_VideoStatus_Name(CaptureStatus_VideoStatus value) { + return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( + static_cast(value)); +} +inline bool CaptureStatus_VideoStatus_Parse(absl::string_view name, CaptureStatus_VideoStatus* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + CaptureStatus_VideoStatus_descriptor(), name, value); +} enum TakePhotoFeedback : int { TAKE_PHOTO_FEEDBACK_UNKNOWN = 0, TAKE_PHOTO_FEEDBACK_OK = 1, @@ -2601,25 +2781,24 @@ class SetModeResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { +class SubscribeStorageInformationRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) */ { public: - inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} - ~RespondTakePhotoRequest() override; + inline SubscribeStorageInformationRequest() : SubscribeStorageInformationRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoRequest(const RespondTakePhotoRequest& from); - RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept - : RespondTakePhotoRequest() { + SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from); + SubscribeStorageInformationRequest(SubscribeStorageInformationRequest&& from) noexcept + : SubscribeStorageInformationRequest() { *this = ::std::move(from); } - inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + inline SubscribeStorageInformationRequest& operator=(const SubscribeStorageInformationRequest& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + inline SubscribeStorageInformationRequest& operator=(SubscribeStorageInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2649,20 +2828,20 @@ class RespondTakePhotoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoRequest& default_instance() { + static const SubscribeStorageInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoRequest_default_instance_); + static inline const SubscribeStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = 16; - friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoRequest* other) { + inline void Swap(SubscribeStorageInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2675,7 +2854,7 @@ class RespondTakePhotoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + void UnsafeArenaSwap(SubscribeStorageInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2683,40 +2862,26 @@ class RespondTakePhotoRequest final : // implements Message ---------------------------------------------- - RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoRequest& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoRequest& from) { - RespondTakePhotoRequest::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStorageInformationRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStorageInformationRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + return "mavsdk.rpc.camera_server.SubscribeStorageInformationRequest"; } protected: - explicit RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2728,35 +2893,7 @@ class RespondTakePhotoRequest final : // accessors ------------------------------------------------------- - enum : int { - kCaptureInfoFieldNumber = 2, - kTakePhotoFeedbackFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - bool has_capture_info() const; - void clear_capture_info() ; - const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); - ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); - void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - private: - const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; - ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); - public: - void unsafe_arena_set_allocated_capture_info( - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - void clear_take_photo_feedback() ; - ::mavsdk::rpc::camera_server::TakePhotoFeedback take_photo_feedback() const; - void set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - private: - ::mavsdk::rpc::camera_server::TakePhotoFeedback _internal_take_photo_feedback() const; - void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) private: class _Internal; @@ -2764,34 +2901,29 @@ class RespondTakePhotoRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; - int take_photo_feedback_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { +class StorageInformationResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformationResponse) */ { public: - inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} - ~RespondTakePhotoResponse() override; + inline StorageInformationResponse() : StorageInformationResponse(nullptr) {} + ~StorageInformationResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoResponse(const RespondTakePhotoResponse& from); - RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept - : RespondTakePhotoResponse() { + StorageInformationResponse(const StorageInformationResponse& from); + StorageInformationResponse(StorageInformationResponse&& from) noexcept + : StorageInformationResponse() { *this = ::std::move(from); } - inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + inline StorageInformationResponse& operator=(const StorageInformationResponse& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + inline StorageInformationResponse& operator=(StorageInformationResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2821,20 +2953,20 @@ class RespondTakePhotoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoResponse& default_instance() { + static const StorageInformationResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoResponse_default_instance_); + static inline const StorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_StorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = 17; - friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoResponse* other) { + inline void Swap(StorageInformationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2847,7 +2979,7 @@ class RespondTakePhotoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + void UnsafeArenaSwap(StorageInformationResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2855,14 +2987,14 @@ class RespondTakePhotoResponse final : // implements Message ---------------------------------------------- - RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoResponse& from); + void CopyFrom(const StorageInformationResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoResponse& from) { - RespondTakePhotoResponse::MergeImpl(*this, from); + void MergeFrom( const StorageInformationResponse& from) { + StorageInformationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -2880,15 +3012,15 @@ class RespondTakePhotoResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoResponse* other); + void InternalSwap(StorageInformationResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + return "mavsdk.rpc.camera_server.StorageInformationResponse"; } protected: - explicit RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2901,23 +3033,19 @@ class RespondTakePhotoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kStorageIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - bool has_camera_server_result() const; - void clear_camera_server_result() ; - const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); - ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); - void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); + private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); + public: - void unsafe_arena_set_allocated_camera_server_result( - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); - ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformationResponse) private: class _Internal; @@ -2925,33 +3053,32 @@ class RespondTakePhotoResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + ::int32_t storage_id_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Information final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { +class RespondStorageInformationRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationRequest) */ { public: - inline Information() : Information(nullptr) {} - ~Information() override; + inline RespondStorageInformationRequest() : RespondStorageInformationRequest(nullptr) {} + ~RespondStorageInformationRequest() override; template - explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Information(const Information& from); - Information(Information&& from) noexcept - : Information() { + RespondStorageInformationRequest(const RespondStorageInformationRequest& from); + RespondStorageInformationRequest(RespondStorageInformationRequest&& from) noexcept + : RespondStorageInformationRequest() { *this = ::std::move(from); } - inline Information& operator=(const Information& from) { + inline RespondStorageInformationRequest& operator=(const RespondStorageInformationRequest& from) { CopyFrom(from); return *this; } - inline Information& operator=(Information&& from) noexcept { + inline RespondStorageInformationRequest& operator=(RespondStorageInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2981,20 +3108,20 @@ class Information final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Information& default_instance() { + static const RespondStorageInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const Information* internal_default_instance() { - return reinterpret_cast( - &_Information_default_instance_); + static inline const RespondStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = 18; - friend void swap(Information& a, Information& b) { + friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { a.Swap(&b); } - inline void Swap(Information* other) { + inline void Swap(RespondStorageInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3007,7 +3134,7 @@ class Information final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Information* other) { + void UnsafeArenaSwap(RespondStorageInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3015,14 +3142,14 @@ class Information final : // implements Message ---------------------------------------------- - Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Information& from); + void CopyFrom(const RespondStorageInformationRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Information& from) { - Information::MergeImpl(*this, from); + void MergeFrom( const RespondStorageInformationRequest& from) { + RespondStorageInformationRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3040,15 +3167,15 @@ class Information final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Information* other); + void InternalSwap(RespondStorageInformationRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Information"; + return "mavsdk.rpc.camera_server.RespondStorageInformationRequest"; } protected: - explicit Information(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3061,212 +3188,1845 @@ class Information final : // accessors ------------------------------------------------------- enum : int { - kVendorNameFieldNumber = 1, - kModelNameFieldNumber = 2, - kFirmwareVersionFieldNumber = 3, - kDefinitionFileUriFieldNumber = 11, - kFocalLengthMmFieldNumber = 4, - kHorizontalSensorSizeMmFieldNumber = 5, - kVerticalSensorSizeMmFieldNumber = 6, - kHorizontalResolutionPxFieldNumber = 7, - kVerticalResolutionPxFieldNumber = 8, - kLensIdFieldNumber = 9, - kDefinitionFileVersionFieldNumber = 10, + kStorageInformationFieldNumber = 1, }; - // string vendor_name = 1; - void clear_vendor_name() ; - const std::string& vendor_name() const; - - - - - template - void set_vendor_name(Arg_&& arg, Args_... args); - std::string* mutable_vendor_name(); - PROTOBUF_NODISCARD std::string* release_vendor_name(); - void set_allocated_vendor_name(std::string* ptr); - + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; + bool has_storage_information() const; + void clear_storage_information() ; + const ::mavsdk::rpc::camera_server::StorageInformation& storage_information() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::StorageInformation* release_storage_information(); + ::mavsdk::rpc::camera_server::StorageInformation* mutable_storage_information(); + void set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* storage_information); private: - const std::string& _internal_vendor_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( - const std::string& value); - std::string* _internal_mutable_vendor_name(); - + const ::mavsdk::rpc::camera_server::StorageInformation& _internal_storage_information() const; + ::mavsdk::rpc::camera_server::StorageInformation* _internal_mutable_storage_information(); public: - // string model_name = 2; - void clear_model_name() ; - const std::string& model_name() const; + void unsafe_arena_set_allocated_storage_information( + ::mavsdk::rpc::camera_server::StorageInformation* storage_information); + ::mavsdk::rpc::camera_server::StorageInformation* unsafe_arena_release_storage_information(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + private: + class _Internal; + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::StorageInformation* storage_information_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- +class RespondStorageInformationResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationResponse) */ { + public: + inline RespondStorageInformationResponse() : RespondStorageInformationResponse(nullptr) {} + ~RespondStorageInformationResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + RespondStorageInformationResponse(const RespondStorageInformationResponse& from); + RespondStorageInformationResponse(RespondStorageInformationResponse&& from) noexcept + : RespondStorageInformationResponse() { + *this = ::std::move(from); + } - template - void set_model_name(Arg_&& arg, Args_... args); - std::string* mutable_model_name(); - PROTOBUF_NODISCARD std::string* release_model_name(); - void set_allocated_model_name(std::string* ptr); + inline RespondStorageInformationResponse& operator=(const RespondStorageInformationResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStorageInformationResponse& operator=(RespondStorageInformationResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondStorageInformationResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondStorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 19; + + friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondStorageInformationResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondStorageInformationResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondStorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondStorageInformationResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondStorageInformationResponse& from) { + RespondStorageInformationResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondStorageInformationResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondStorageInformationResponse"; + } + protected: + explicit RespondStorageInformationResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeCaptureStatusRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) */ { + public: + inline SubscribeCaptureStatusRequest() : SubscribeCaptureStatusRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from); + SubscribeCaptureStatusRequest(SubscribeCaptureStatusRequest&& from) noexcept + : SubscribeCaptureStatusRequest() { + *this = ::std::move(from); + } + + inline SubscribeCaptureStatusRequest& operator=(const SubscribeCaptureStatusRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeCaptureStatusRequest& operator=(SubscribeCaptureStatusRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeCaptureStatusRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCaptureStatusRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 20; + + friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeCaptureStatusRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeCaptureStatusRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeCaptureStatusRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeCaptureStatusRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest"; + } + protected: + explicit SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CaptureStatusResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatusResponse) */ { + public: + inline CaptureStatusResponse() : CaptureStatusResponse(nullptr) {} + ~CaptureStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CaptureStatusResponse(const CaptureStatusResponse& from); + CaptureStatusResponse(CaptureStatusResponse&& from) noexcept + : CaptureStatusResponse() { + *this = ::std::move(from); + } + + inline CaptureStatusResponse& operator=(const CaptureStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline CaptureStatusResponse& operator=(CaptureStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CaptureStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const CaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 21; + + friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(CaptureStatusResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CaptureStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CaptureStatusResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const CaptureStatusResponse& from) { + CaptureStatusResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CaptureStatusResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.CaptureStatusResponse"; + } + protected: + explicit CaptureStatusResponse(::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 { + kReservedFieldNumber = 1, + }; + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); + + private: + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatusResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t reserved_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondCaptureStatusRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) */ { + public: + inline RespondCaptureStatusRequest() : RespondCaptureStatusRequest(nullptr) {} + ~RespondCaptureStatusRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from); + RespondCaptureStatusRequest(RespondCaptureStatusRequest&& from) noexcept + : RespondCaptureStatusRequest() { + *this = ::std::move(from); + } + + inline RespondCaptureStatusRequest& operator=(const RespondCaptureStatusRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondCaptureStatusRequest& operator=(RespondCaptureStatusRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondCaptureStatusRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 22; + + friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondCaptureStatusRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondCaptureStatusRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondCaptureStatusRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondCaptureStatusRequest& from) { + RespondCaptureStatusRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondCaptureStatusRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondCaptureStatusRequest"; + } + protected: + explicit RespondCaptureStatusRequest(::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 { + kCaptureStatusFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; + bool has_capture_status() const; + void clear_capture_status() ; + const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureStatus* release_capture_status(); + ::mavsdk::rpc::camera_server::CaptureStatus* mutable_capture_status(); + void set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* capture_status); + private: + const ::mavsdk::rpc::camera_server::CaptureStatus& _internal_capture_status() const; + ::mavsdk::rpc::camera_server::CaptureStatus* _internal_mutable_capture_status(); + public: + void unsafe_arena_set_allocated_capture_status( + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status); + ::mavsdk::rpc::camera_server::CaptureStatus* unsafe_arena_release_capture_status(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondCaptureStatusResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) */ { + public: + inline RespondCaptureStatusResponse() : RespondCaptureStatusResponse(nullptr) {} + ~RespondCaptureStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from); + RespondCaptureStatusResponse(RespondCaptureStatusResponse&& from) noexcept + : RespondCaptureStatusResponse() { + *this = ::std::move(from); + } + + inline RespondCaptureStatusResponse& operator=(const RespondCaptureStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondCaptureStatusResponse& operator=(RespondCaptureStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondCaptureStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondCaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 23; + + friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondCaptureStatusResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondCaptureStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondCaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondCaptureStatusResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondCaptureStatusResponse& from) { + RespondCaptureStatusResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondCaptureStatusResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondCaptureStatusResponse"; + } + protected: + explicit RespondCaptureStatusResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondTakePhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { + public: + inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} + ~RespondTakePhotoRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondTakePhotoRequest(const RespondTakePhotoRequest& from); + RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept + : RespondTakePhotoRequest() { + *this = ::std::move(from); + } + + inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondTakePhotoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 24; + + friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoRequest& from) { + RespondTakePhotoRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondTakePhotoRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + } + protected: + explicit RespondTakePhotoRequest(::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 { + kCaptureInfoFieldNumber = 2, + kTakePhotoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + bool has_capture_info() const; + void clear_capture_info() ; + const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); + ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); + void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + private: + const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; + ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); + public: + void unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); + // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + void clear_take_photo_feedback() ; + ::mavsdk::rpc::camera_server::TakePhotoFeedback take_photo_feedback() const; + void set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); + + private: + ::mavsdk::rpc::camera_server::TakePhotoFeedback _internal_take_photo_feedback() const; + void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; + int take_photo_feedback_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondTakePhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { + public: + inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} + ~RespondTakePhotoResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondTakePhotoResponse(const RespondTakePhotoResponse& from); + RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept + : RespondTakePhotoResponse() { + *this = ::std::move(from); + } + + inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondTakePhotoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 25; + + friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoResponse& from) { + RespondTakePhotoResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondTakePhotoResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + } + protected: + explicit RespondTakePhotoResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Information final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { + public: + inline Information() : Information(nullptr) {} + ~Information() override; + template + explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Information(const Information& from); + Information(Information&& from) noexcept + : Information() { + *this = ::std::move(from); + } + + inline Information& operator=(const Information& from) { + CopyFrom(from); + return *this; + } + inline Information& operator=(Information&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Information& default_instance() { + return *internal_default_instance(); + } + static inline const Information* internal_default_instance() { + return reinterpret_cast( + &_Information_default_instance_); + } + static constexpr int kIndexInFileMessages = + 26; + + friend void swap(Information& a, Information& b) { + a.Swap(&b); + } + inline void Swap(Information* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Information* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Information& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Information& from) { + Information::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Information* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Information"; + } + protected: + explicit Information(::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 { + kVendorNameFieldNumber = 1, + kModelNameFieldNumber = 2, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, + }; + // string vendor_name = 1; + void clear_vendor_name() ; + const std::string& vendor_name() const; + + + + + template + void set_vendor_name(Arg_&& arg, Args_... args); + std::string* mutable_vendor_name(); + PROTOBUF_NODISCARD std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* ptr); + + private: + const std::string& _internal_vendor_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( + const std::string& value); + std::string* _internal_mutable_vendor_name(); + + public: + // string model_name = 2; + void clear_model_name() ; + const std::string& model_name() const; + + + + + template + void set_model_name(Arg_&& arg, Args_... args); + std::string* mutable_model_name(); + PROTOBUF_NODISCARD std::string* release_model_name(); + void set_allocated_model_name(std::string* ptr); + + private: + const std::string& _internal_model_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( + const std::string& value); + std::string* _internal_mutable_model_name(); + + public: + // string firmware_version = 3; + void clear_firmware_version() ; + const std::string& firmware_version() const; + + + + + template + void set_firmware_version(Arg_&& arg, Args_... args); + std::string* mutable_firmware_version(); + PROTOBUF_NODISCARD std::string* release_firmware_version(); + void set_allocated_firmware_version(std::string* ptr); + + private: + const std::string& _internal_firmware_version() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version( + const std::string& value); + std::string* _internal_mutable_firmware_version(); + + public: + // string definition_file_uri = 11; + void clear_definition_file_uri() ; + const std::string& definition_file_uri() const; + + + + + template + void set_definition_file_uri(Arg_&& arg, Args_... args); + std::string* mutable_definition_file_uri(); + PROTOBUF_NODISCARD std::string* release_definition_file_uri(); + void set_allocated_definition_file_uri(std::string* ptr); + + private: + const std::string& _internal_definition_file_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri( + const std::string& value); + std::string* _internal_mutable_definition_file_uri(); + + public: + // float focal_length_mm = 4; + void clear_focal_length_mm() ; + float focal_length_mm() const; + void set_focal_length_mm(float value); private: - const std::string& _internal_model_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( - const std::string& value); - std::string* _internal_mutable_model_name(); + float _internal_focal_length_mm() const; + void _internal_set_focal_length_mm(float value); + + public: + // float horizontal_sensor_size_mm = 5; + void clear_horizontal_sensor_size_mm() ; + float horizontal_sensor_size_mm() const; + void set_horizontal_sensor_size_mm(float value); + + private: + float _internal_horizontal_sensor_size_mm() const; + void _internal_set_horizontal_sensor_size_mm(float value); + + public: + // float vertical_sensor_size_mm = 6; + void clear_vertical_sensor_size_mm() ; + float vertical_sensor_size_mm() const; + void set_vertical_sensor_size_mm(float value); + + private: + float _internal_vertical_sensor_size_mm() const; + void _internal_set_vertical_sensor_size_mm(float value); + + public: + // uint32 horizontal_resolution_px = 7; + void clear_horizontal_resolution_px() ; + ::uint32_t horizontal_resolution_px() const; + void set_horizontal_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_horizontal_resolution_px() const; + void _internal_set_horizontal_resolution_px(::uint32_t value); + + public: + // uint32 vertical_resolution_px = 8; + void clear_vertical_resolution_px() ; + ::uint32_t vertical_resolution_px() const; + void set_vertical_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_vertical_resolution_px() const; + void _internal_set_vertical_resolution_px(::uint32_t value); + + public: + // uint32 lens_id = 9; + void clear_lens_id() ; + ::uint32_t lens_id() const; + void set_lens_id(::uint32_t value); + + private: + ::uint32_t _internal_lens_id() const; + void _internal_set_lens_id(::uint32_t value); + + public: + // uint32 definition_file_version = 10; + void clear_definition_file_version() ; + ::uint32_t definition_file_version() const; + void set_definition_file_version(::uint32_t value); + + private: + ::uint32_t _internal_definition_file_version() const; + void _internal_set_definition_file_version(::uint32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; + float focal_length_mm_; + float horizontal_sensor_size_mm_; + float vertical_sensor_size_mm_; + ::uint32_t horizontal_resolution_px_; + ::uint32_t vertical_resolution_px_; + ::uint32_t lens_id_; + ::uint32_t definition_file_version_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Position final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { + public: + inline Position() : Position(nullptr) {} + ~Position() override; + template + explicit PROTOBUF_CONSTEXPR Position(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Position(const Position& from); + Position(Position&& from) noexcept + : Position() { + *this = ::std::move(from); + } + + inline Position& operator=(const Position& from) { + CopyFrom(from); + return *this; + } + inline Position& operator=(Position&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Position& default_instance() { + return *internal_default_instance(); + } + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); + } + static constexpr int kIndexInFileMessages = + 27; + + friend void swap(Position& a, Position& b) { + a.Swap(&b); + } + inline void Swap(Position* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Position* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Position* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Position& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Position& from) { + Position::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Position* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Position"; + } + protected: + explicit Position(::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 { + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 4, + }; + // double latitude_deg = 1; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); + + private: + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); + + public: + // double longitude_deg = 2; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); + + private: + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); + + public: + // float absolute_altitude_m = 3; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + private: + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); public: - // string firmware_version = 3; - void clear_firmware_version() ; - const std::string& firmware_version() const; + // float relative_altitude_m = 4; + void clear_relative_altitude_m() ; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); + private: + float _internal_relative_altitude_m() const; + void _internal_set_relative_altitude_m(float value); + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) + private: + class _Internal; + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- - template - void set_firmware_version(Arg_&& arg, Args_... args); - std::string* mutable_firmware_version(); - PROTOBUF_NODISCARD std::string* release_firmware_version(); - void set_allocated_firmware_version(std::string* ptr); +class Quaternion final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { + public: + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; + template + explicit PROTOBUF_CONSTEXPR Quaternion(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - private: - const std::string& _internal_firmware_version() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version( - const std::string& value); - std::string* _internal_mutable_firmware_version(); + Quaternion(const Quaternion& from); + Quaternion(Quaternion&& from) noexcept + : Quaternion() { + *this = ::std::move(from); + } - public: - // string definition_file_uri = 11; - void clear_definition_file_uri() ; - const std::string& definition_file_uri() const; + inline Quaternion& operator=(const Quaternion& from) { + CopyFrom(from); + return *this; + } + inline Quaternion& operator=(Quaternion&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + 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 Quaternion& default_instance() { + return *internal_default_instance(); + } + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); + } + static constexpr int kIndexInFileMessages = + 28; + friend void swap(Quaternion& a, Quaternion& b) { + a.Swap(&b); + } + inline void Swap(Quaternion* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Quaternion* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } - template - void set_definition_file_uri(Arg_&& arg, Args_... args); - std::string* mutable_definition_file_uri(); - PROTOBUF_NODISCARD std::string* release_definition_file_uri(); - void set_allocated_definition_file_uri(std::string* ptr); + // implements Message ---------------------------------------------- + Quaternion* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Quaternion& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Quaternion& from) { + Quaternion::MergeImpl(*this, from); + } private: - const std::string& _internal_definition_file_uri() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri( - const std::string& value); - std::string* _internal_mutable_definition_file_uri(); - + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); public: - // float focal_length_mm = 4; - void clear_focal_length_mm() ; - float focal_length_mm() const; - void set_focal_length_mm(float value); + 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; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } private: - float _internal_focal_length_mm() const; - void _internal_set_focal_length_mm(float value); + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Quaternion* other); + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Quaternion"; + } + protected: + explicit Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: - // float horizontal_sensor_size_mm = 5; - void clear_horizontal_sensor_size_mm() ; - float horizontal_sensor_size_mm() const; - void set_horizontal_sensor_size_mm(float value); - private: - float _internal_horizontal_sensor_size_mm() const; - void _internal_set_horizontal_sensor_size_mm(float value); + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - public: - // float vertical_sensor_size_mm = 6; - void clear_vertical_sensor_size_mm() ; - float vertical_sensor_size_mm() const; - void set_vertical_sensor_size_mm(float value); + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - private: - float _internal_vertical_sensor_size_mm() const; - void _internal_set_vertical_sensor_size_mm(float value); + // nested types ---------------------------------------------------- - public: - // uint32 horizontal_resolution_px = 7; - void clear_horizontal_resolution_px() ; - ::uint32_t horizontal_resolution_px() const; - void set_horizontal_resolution_px(::uint32_t value); + // accessors ------------------------------------------------------- + + enum : int { + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 4, + }; + // float w = 1; + void clear_w() ; + float w() const; + void set_w(float value); private: - ::uint32_t _internal_horizontal_resolution_px() const; - void _internal_set_horizontal_resolution_px(::uint32_t value); + float _internal_w() const; + void _internal_set_w(float value); public: - // uint32 vertical_resolution_px = 8; - void clear_vertical_resolution_px() ; - ::uint32_t vertical_resolution_px() const; - void set_vertical_resolution_px(::uint32_t value); + // float x = 2; + void clear_x() ; + float x() const; + void set_x(float value); private: - ::uint32_t _internal_vertical_resolution_px() const; - void _internal_set_vertical_resolution_px(::uint32_t value); + float _internal_x() const; + void _internal_set_x(float value); public: - // uint32 lens_id = 9; - void clear_lens_id() ; - ::uint32_t lens_id() const; - void set_lens_id(::uint32_t value); + // float y = 3; + void clear_y() ; + float y() const; + void set_y(float value); private: - ::uint32_t _internal_lens_id() const; - void _internal_set_lens_id(::uint32_t value); + float _internal_y() const; + void _internal_set_y(float value); public: - // uint32 definition_file_version = 10; - void clear_definition_file_version() ; - ::uint32_t definition_file_version() const; - void set_definition_file_version(::uint32_t value); + // float z = 4; + void clear_z() ; + float z() const; + void set_z(float value); private: - ::uint32_t _internal_definition_file_version() const; - void _internal_set_definition_file_version(::uint32_t value); + float _internal_z() const; + void _internal_set_z(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; - float focal_length_mm_; - float horizontal_sensor_size_mm_; - float vertical_sensor_size_mm_; - ::uint32_t horizontal_resolution_px_; - ::uint32_t vertical_resolution_px_; - ::uint32_t lens_id_; - ::uint32_t definition_file_version_; + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + float w_; + float x_; + float y_; + float z_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Position final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { +class CaptureInfo final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { public: - inline Position() : Position(nullptr) {} - ~Position() override; + inline CaptureInfo() : CaptureInfo(nullptr) {} + ~CaptureInfo() override; template - explicit PROTOBUF_CONSTEXPR Position(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CaptureInfo(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Position(const Position& from); - Position(Position&& from) noexcept - : Position() { + CaptureInfo(const CaptureInfo& from); + CaptureInfo(CaptureInfo&& from) noexcept + : CaptureInfo() { *this = ::std::move(from); } - inline Position& operator=(const Position& from) { + inline CaptureInfo& operator=(const CaptureInfo& from) { CopyFrom(from); return *this; } - inline Position& operator=(Position&& from) noexcept { + inline CaptureInfo& operator=(CaptureInfo&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3296,20 +5056,20 @@ class Position final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Position& default_instance() { + static const CaptureInfo& default_instance() { return *internal_default_instance(); } - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const CaptureInfo* internal_default_instance() { + return reinterpret_cast( + &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 29; - friend void swap(Position& a, Position& b) { + friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); } - inline void Swap(Position* other) { + inline void Swap(CaptureInfo* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3322,7 +5082,7 @@ class Position final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Position* other) { + void UnsafeArenaSwap(CaptureInfo* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3330,14 +5090,14 @@ class Position final : // implements Message ---------------------------------------------- - Position* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CaptureInfo* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Position& from); + void CopyFrom(const CaptureInfo& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Position& from) { - Position::MergeImpl(*this, from); + void MergeFrom( const CaptureInfo& from) { + CaptureInfo::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3355,15 +5115,15 @@ class Position final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Position* other); + void InternalSwap(CaptureInfo* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Position"; + return "mavsdk.rpc.camera_server.CaptureInfo"; } protected: - explicit Position(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3376,52 +5136,92 @@ class Position final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, - kRelativeAltitudeMFieldNumber = 4, + kFileUrlFieldNumber = 6, + kPositionFieldNumber = 1, + kAttitudeQuaternionFieldNumber = 2, + kTimeUtcUsFieldNumber = 3, + kIsSuccessFieldNumber = 4, + kIndexFieldNumber = 5, }; - // double latitude_deg = 1; - void clear_latitude_deg() ; - double latitude_deg() const; - void set_latitude_deg(double value); + // string file_url = 6; + void clear_file_url() ; + const std::string& file_url() const; + + + + + template + void set_file_url(Arg_&& arg, Args_... args); + std::string* mutable_file_url(); + PROTOBUF_NODISCARD std::string* release_file_url(); + void set_allocated_file_url(std::string* ptr); private: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); + const std::string& _internal_file_url() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( + const std::string& value); + std::string* _internal_mutable_file_url(); public: - // double longitude_deg = 2; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); + // .mavsdk.rpc.camera_server.Position position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::camera_server::Position& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); + ::mavsdk::rpc::camera_server::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::camera_server::Position* position); + private: + const ::mavsdk::rpc::camera_server::Position& _internal_position() const; + ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); + public: + void unsafe_arena_set_allocated_position( + ::mavsdk::rpc::camera_server::Position* position); + ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + bool has_attitude_quaternion() const; + void clear_attitude_quaternion() ; + const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); + ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); + void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + private: + const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; + ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); + public: + void unsafe_arena_set_allocated_attitude_quaternion( + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); + // uint64 time_utc_us = 3; + void clear_time_utc_us() ; + ::uint64_t time_utc_us() const; + void set_time_utc_us(::uint64_t value); private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); + ::uint64_t _internal_time_utc_us() const; + void _internal_set_time_utc_us(::uint64_t value); public: - // float absolute_altitude_m = 3; - void clear_absolute_altitude_m() ; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); + // bool is_success = 4; + void clear_is_success() ; + bool is_success() const; + void set_is_success(bool value); private: - float _internal_absolute_altitude_m() const; - void _internal_set_absolute_altitude_m(float value); + bool _internal_is_success() const; + void _internal_set_is_success(bool value); public: - // float relative_altitude_m = 4; - void clear_relative_altitude_m() ; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); + // int32 index = 5; + void clear_index() ; + ::int32_t index() const; + void set_index(::int32_t value); private: - float _internal_relative_altitude_m() const; - void _internal_set_relative_altitude_m(float value); + ::int32_t _internal_index() const; + void _internal_set_index(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) private: class _Internal; @@ -3429,35 +5229,38 @@ class Position final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - double latitude_deg_; - double longitude_deg_; - float absolute_altitude_m_; - float relative_altitude_m_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr file_url_; + ::mavsdk::rpc::camera_server::Position* position_; + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; + ::uint64_t time_utc_us_; + bool is_success_; + ::int32_t index_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Quaternion final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { +class CameraServerResult final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline CameraServerResult() : CameraServerResult(nullptr) {} + ~CameraServerResult() override; template - explicit PROTOBUF_CONSTEXPR Quaternion(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CameraServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Quaternion(const Quaternion& from); - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + CameraServerResult(const CameraServerResult& from); + CameraServerResult(CameraServerResult&& from) noexcept + : CameraServerResult() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline CameraServerResult& operator=(const CameraServerResult& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3487,20 +5290,20 @@ class Quaternion final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const CameraServerResult& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const CameraServerResult* internal_default_instance() { + return reinterpret_cast( + &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 30; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(CameraServerResult* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3513,7 +5316,7 @@ class Quaternion final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(CameraServerResult* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3521,14 +5324,14 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CameraServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const CameraServerResult& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const CameraServerResult& from) { + CameraServerResult::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3546,73 +5349,88 @@ class Quaternion final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Quaternion* other); + void InternalSwap(CameraServerResult* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Quaternion"; + return "mavsdk.rpc.camera_server.CameraServerResult"; + } + protected: + explicit CameraServerResult(::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 ---------------------------------------------------- + + using Result = CameraServerResult_Result; + static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; + static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; + static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; + static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; + static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; + static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; + static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; + static inline bool Result_IsValid(int value) { + return CameraServerResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; + static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Result_descriptor() { + return CameraServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return CameraServerResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return CameraServerResult_Result_Parse(name, value); } - protected: - explicit Quaternion(::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 { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, }; - // float w = 1; - void clear_w() ; - float w() const; - void set_w(float value); + // string result_str = 2; + void clear_result_str() ; + const std::string& result_str() const; - private: - float _internal_w() const; - void _internal_set_w(float value); - public: - // float x = 2; - void clear_x() ; - float x() const; - void set_x(float value); - private: - float _internal_x() const; - void _internal_set_x(float value); - public: - // float y = 3; - void clear_y() ; - float y() const; - void set_y(float value); + template + void set_result_str(Arg_&& arg, Args_... args); + std::string* mutable_result_str(); + PROTOBUF_NODISCARD std::string* release_result_str(); + void set_allocated_result_str(std::string* ptr); private: - float _internal_y() const; - void _internal_set_y(float value); + 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: - // float z = 4; - void clear_z() ; - float z() const; - void set_z(float value); + // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; + void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); private: - float _internal_z() const; - void _internal_set_z(float value); + ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) private: class _Internal; @@ -3620,35 +5438,33 @@ class Quaternion final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - float w_; - float x_; - float y_; - float z_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; + int result_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureInfo final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { +class StorageInformation final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformation) */ { public: - inline CaptureInfo() : CaptureInfo(nullptr) {} - ~CaptureInfo() override; + inline StorageInformation() : StorageInformation(nullptr) {} + ~StorageInformation() override; template - explicit PROTOBUF_CONSTEXPR CaptureInfo(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StorageInformation(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CaptureInfo(const CaptureInfo& from); - CaptureInfo(CaptureInfo&& from) noexcept - : CaptureInfo() { + StorageInformation(const StorageInformation& from); + StorageInformation(StorageInformation&& from) noexcept + : StorageInformation() { *this = ::std::move(from); } - inline CaptureInfo& operator=(const CaptureInfo& from) { + inline StorageInformation& operator=(const StorageInformation& from) { CopyFrom(from); return *this; } - inline CaptureInfo& operator=(CaptureInfo&& from) noexcept { + inline StorageInformation& operator=(StorageInformation&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3678,20 +5494,20 @@ class CaptureInfo final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureInfo& default_instance() { + static const StorageInformation& default_instance() { return *internal_default_instance(); } - static inline const CaptureInfo* internal_default_instance() { - return reinterpret_cast( - &_CaptureInfo_default_instance_); + static inline const StorageInformation* internal_default_instance() { + return reinterpret_cast( + &_StorageInformation_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 31; - friend void swap(CaptureInfo& a, CaptureInfo& b) { + friend void swap(StorageInformation& a, StorageInformation& b) { a.Swap(&b); } - inline void Swap(CaptureInfo* other) { + inline void Swap(StorageInformation* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3704,7 +5520,7 @@ class CaptureInfo final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureInfo* other) { + void UnsafeArenaSwap(StorageInformation* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3712,14 +5528,14 @@ class CaptureInfo final : // implements Message ---------------------------------------------- - CaptureInfo* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StorageInformation* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CaptureInfo& from); + void CopyFrom(const StorageInformation& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CaptureInfo& from) { - CaptureInfo::MergeImpl(*this, from); + void MergeFrom( const StorageInformation& from) { + StorageInformation::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3737,15 +5553,15 @@ class CaptureInfo final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CaptureInfo* other); + void InternalSwap(StorageInformation* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureInfo"; + return "mavsdk.rpc.camera_server.StorageInformation"; } protected: - explicit CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StorageInformation(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3755,95 +5571,145 @@ class CaptureInfo final : // nested types ---------------------------------------------------- + using StorageStatus = StorageInformation_StorageStatus; + static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; + static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; + static constexpr StorageStatus STORAGE_STATUS_FORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; + static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; + static inline bool StorageStatus_IsValid(int value) { + return StorageInformation_StorageStatus_IsValid(value); + } + static constexpr StorageStatus StorageStatus_MIN = StorageInformation_StorageStatus_StorageStatus_MIN; + static constexpr StorageStatus StorageStatus_MAX = StorageInformation_StorageStatus_StorageStatus_MAX; + static constexpr int StorageStatus_ARRAYSIZE = StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageStatus_descriptor() { + return StorageInformation_StorageStatus_descriptor(); + } + template + static inline const std::string& StorageStatus_Name(T value) { + return StorageInformation_StorageStatus_Name(value); + } + static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { + return StorageInformation_StorageStatus_Parse(name, value); + } + + using StorageType = StorageInformation_StorageType; + static constexpr StorageType STORAGE_TYPE_UNKNOWN = StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; + static constexpr StorageType STORAGE_TYPE_USB_STICK = StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; + static constexpr StorageType STORAGE_TYPE_SD = StorageInformation_StorageType_STORAGE_TYPE_SD; + static constexpr StorageType STORAGE_TYPE_MICROSD = StorageInformation_StorageType_STORAGE_TYPE_MICROSD; + static constexpr StorageType STORAGE_TYPE_HD = StorageInformation_StorageType_STORAGE_TYPE_HD; + static constexpr StorageType STORAGE_TYPE_OTHER = StorageInformation_StorageType_STORAGE_TYPE_OTHER; + static inline bool StorageType_IsValid(int value) { + return StorageInformation_StorageType_IsValid(value); + } + static constexpr StorageType StorageType_MIN = StorageInformation_StorageType_StorageType_MIN; + static constexpr StorageType StorageType_MAX = StorageInformation_StorageType_StorageType_MAX; + static constexpr int StorageType_ARRAYSIZE = StorageInformation_StorageType_StorageType_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageType_descriptor() { + return StorageInformation_StorageType_descriptor(); + } + template + static inline const std::string& StorageType_Name(T value) { + return StorageInformation_StorageType_Name(value); + } + static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { + return StorageInformation_StorageType_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kFileUrlFieldNumber = 6, - kPositionFieldNumber = 1, - kAttitudeQuaternionFieldNumber = 2, - kTimeUtcUsFieldNumber = 3, - kIsSuccessFieldNumber = 4, - kIndexFieldNumber = 5, + kUsedStorageMibFieldNumber = 1, + kAvailableStorageMibFieldNumber = 2, + kTotalStorageMibFieldNumber = 3, + kStorageStatusFieldNumber = 4, + kStorageIdFieldNumber = 5, + kStorageTypeFieldNumber = 6, + kReadSpeedFieldNumber = 7, + kWriteSpeedFieldNumber = 8, }; - // string file_url = 6; - void clear_file_url() ; - const std::string& file_url() const; + // float used_storage_mib = 1; + void clear_used_storage_mib() ; + float used_storage_mib() const; + void set_used_storage_mib(float value); + private: + float _internal_used_storage_mib() const; + void _internal_set_used_storage_mib(float value); + public: + // float available_storage_mib = 2; + void clear_available_storage_mib() ; + float available_storage_mib() const; + void set_available_storage_mib(float value); + private: + float _internal_available_storage_mib() const; + void _internal_set_available_storage_mib(float value); - template - void set_file_url(Arg_&& arg, Args_... args); - std::string* mutable_file_url(); - PROTOBUF_NODISCARD std::string* release_file_url(); - void set_allocated_file_url(std::string* ptr); + public: + // float total_storage_mib = 3; + void clear_total_storage_mib() ; + float total_storage_mib() const; + void set_total_storage_mib(float value); private: - const std::string& _internal_file_url() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( - const std::string& value); - std::string* _internal_mutable_file_url(); + float _internal_total_storage_mib() const; + void _internal_set_total_storage_mib(float value); public: - // .mavsdk.rpc.camera_server.Position position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::camera_server::Position& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); - ::mavsdk::rpc::camera_server::Position* mutable_position(); - void set_allocated_position(::mavsdk::rpc::camera_server::Position* position); + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; + void clear_storage_status() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus storage_status() const; + void set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + private: - const ::mavsdk::rpc::camera_server::Position& _internal_position() const; - ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus _internal_storage_status() const; + void _internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + public: - void unsafe_arena_set_allocated_position( - ::mavsdk::rpc::camera_server::Position* position); - ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; - bool has_attitude_quaternion() const; - void clear_attitude_quaternion() ; - const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); - ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); - void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + // uint32 storage_id = 5; + void clear_storage_id() ; + ::uint32_t storage_id() const; + void set_storage_id(::uint32_t value); + private: - const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; - ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); + ::uint32_t _internal_storage_id() const; + void _internal_set_storage_id(::uint32_t value); + public: - void unsafe_arena_set_allocated_attitude_quaternion( - ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); - ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); - // uint64 time_utc_us = 3; - void clear_time_utc_us() ; - ::uint64_t time_utc_us() const; - void set_time_utc_us(::uint64_t value); + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; + void clear_storage_type() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageType storage_type() const; + void set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); private: - ::uint64_t _internal_time_utc_us() const; - void _internal_set_time_utc_us(::uint64_t value); + ::mavsdk::rpc::camera_server::StorageInformation_StorageType _internal_storage_type() const; + void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); public: - // bool is_success = 4; - void clear_is_success() ; - bool is_success() const; - void set_is_success(bool value); + // float read_speed = 7; + void clear_read_speed() ; + float read_speed() const; + void set_read_speed(float value); private: - bool _internal_is_success() const; - void _internal_set_is_success(bool value); + float _internal_read_speed() const; + void _internal_set_read_speed(float value); public: - // int32 index = 5; - void clear_index() ; - ::int32_t index() const; - void set_index(::int32_t value); + // float write_speed = 8; + void clear_write_speed() ; + float write_speed() const; + void set_write_speed(float value); private: - ::int32_t _internal_index() const; - void _internal_set_index(::int32_t value); + float _internal_write_speed() const; + void _internal_set_write_speed(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) private: class _Internal; @@ -3851,38 +5717,39 @@ class CaptureInfo final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + float used_storage_mib_; + float available_storage_mib_; + float total_storage_mib_; + int storage_status_; + ::uint32_t storage_id_; + int storage_type_; + float read_speed_; + float write_speed_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr file_url_; - ::mavsdk::rpc::camera_server::Position* position_; - ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; - ::uint64_t time_utc_us_; - bool is_success_; - ::int32_t index_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CameraServerResult final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { +class CaptureStatus final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatus) */ { public: - inline CameraServerResult() : CameraServerResult(nullptr) {} - ~CameraServerResult() override; + inline CaptureStatus() : CaptureStatus(nullptr) {} + ~CaptureStatus() override; template - explicit PROTOBUF_CONSTEXPR CameraServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR CaptureStatus(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CameraServerResult(const CameraServerResult& from); - CameraServerResult(CameraServerResult&& from) noexcept - : CameraServerResult() { + CaptureStatus(const CaptureStatus& from); + CaptureStatus(CaptureStatus&& from) noexcept + : CaptureStatus() { *this = ::std::move(from); } - inline CameraServerResult& operator=(const CameraServerResult& from) { + inline CaptureStatus& operator=(const CaptureStatus& from) { CopyFrom(from); return *this; } - inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { + inline CaptureStatus& operator=(CaptureStatus&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3912,20 +5779,20 @@ class CameraServerResult final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CameraServerResult& default_instance() { + static const CaptureStatus& default_instance() { return *internal_default_instance(); } - static inline const CameraServerResult* internal_default_instance() { - return reinterpret_cast( - &_CameraServerResult_default_instance_); + static inline const CaptureStatus* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 32; - friend void swap(CameraServerResult& a, CameraServerResult& b) { + friend void swap(CaptureStatus& a, CaptureStatus& b) { a.Swap(&b); } - inline void Swap(CameraServerResult* other) { + inline void Swap(CaptureStatus* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3938,7 +5805,7 @@ class CameraServerResult final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CameraServerResult* other) { + void UnsafeArenaSwap(CaptureStatus* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3946,14 +5813,14 @@ class CameraServerResult final : // implements Message ---------------------------------------------- - CameraServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + CaptureStatus* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CameraServerResult& from); + void CopyFrom(const CaptureStatus& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CameraServerResult& from) { - CameraServerResult::MergeImpl(*this, from); + void MergeFrom( const CaptureStatus& from) { + CaptureStatus::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3971,15 +5838,15 @@ class CameraServerResult final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CameraServerResult* other); + void InternalSwap(CaptureStatus* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CameraServerResult"; + return "mavsdk.rpc.camera_server.CaptureStatus"; } protected: - explicit CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit CaptureStatus(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3989,70 +5856,119 @@ class CameraServerResult final : // nested types ---------------------------------------------------- - using Result = CameraServerResult_Result; - static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; - static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; - static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; - static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; - static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; - static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; - static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; - static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; - static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; - static inline bool Result_IsValid(int value) { - return CameraServerResult_Result_IsValid(value); + using ImageStatus = CaptureStatus_ImageStatus; + static constexpr ImageStatus IMAGE_STATUS_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; + static constexpr ImageStatus IMAGE_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; + static inline bool ImageStatus_IsValid(int value) { + return CaptureStatus_ImageStatus_IsValid(value); } - static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; - static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; - static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Result_descriptor() { - return CameraServerResult_Result_descriptor(); + static constexpr ImageStatus ImageStatus_MIN = CaptureStatus_ImageStatus_ImageStatus_MIN; + static constexpr ImageStatus ImageStatus_MAX = CaptureStatus_ImageStatus_ImageStatus_MAX; + static constexpr int ImageStatus_ARRAYSIZE = CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* ImageStatus_descriptor() { + return CaptureStatus_ImageStatus_descriptor(); } template - static inline const std::string& Result_Name(T value) { - return CameraServerResult_Result_Name(value); + static inline const std::string& ImageStatus_Name(T value) { + return CaptureStatus_ImageStatus_Name(value); } - static inline bool Result_Parse(absl::string_view name, Result* value) { - return CameraServerResult_Result_Parse(name, value); + static inline bool ImageStatus_Parse(absl::string_view name, ImageStatus* value) { + return CaptureStatus_ImageStatus_Parse(name, value); + } + + using VideoStatus = CaptureStatus_VideoStatus; + static constexpr VideoStatus VIDEO_STATUS_IDLE = CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; + static constexpr VideoStatus VIDEO_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; + static inline bool VideoStatus_IsValid(int value) { + return CaptureStatus_VideoStatus_IsValid(value); + } + static constexpr VideoStatus VideoStatus_MIN = CaptureStatus_VideoStatus_VideoStatus_MIN; + static constexpr VideoStatus VideoStatus_MAX = CaptureStatus_VideoStatus_VideoStatus_MAX; + static constexpr int VideoStatus_ARRAYSIZE = CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* VideoStatus_descriptor() { + return CaptureStatus_VideoStatus_descriptor(); + } + template + static inline const std::string& VideoStatus_Name(T value) { + return CaptureStatus_VideoStatus_Name(value); + } + static inline bool VideoStatus_Parse(absl::string_view name, VideoStatus* value) { + return CaptureStatus_VideoStatus_Parse(name, value); } // accessors ------------------------------------------------------- enum : int { - kResultStrFieldNumber = 2, - kResultFieldNumber = 1, + kImageIntervalFieldNumber = 1, + kRecordingTimeSFieldNumber = 2, + kAvailableCapacityFieldNumber = 3, + kImageStatusFieldNumber = 4, + kVideoStatusFieldNumber = 5, + kImageCountFieldNumber = 6, }; - // string result_str = 2; - void clear_result_str() ; - const std::string& result_str() const; + // float image_interval = 1; + void clear_image_interval() ; + float image_interval() const; + void set_image_interval(float value); + private: + float _internal_image_interval() const; + void _internal_set_image_interval(float value); + public: + // float recording_time_s = 2; + void clear_recording_time_s() ; + float recording_time_s() const; + void set_recording_time_s(float value); + private: + float _internal_recording_time_s() const; + void _internal_set_recording_time_s(float value); - template - void set_result_str(Arg_&& arg, Args_... args); - std::string* mutable_result_str(); - PROTOBUF_NODISCARD std::string* release_result_str(); - void set_allocated_result_str(std::string* ptr); + public: + // float available_capacity = 3; + void clear_available_capacity() ; + float available_capacity() const; + void set_available_capacity(float value); + + private: + float _internal_available_capacity() const; + void _internal_set_available_capacity(float value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + void clear_image_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus image_status() const; + void set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + private: + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus _internal_image_status() const; + void _internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + void clear_video_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus video_status() const; + void set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); private: - const std::string& _internal_result_str() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_result_str( - const std::string& value); - std::string* _internal_mutable_result_str(); + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus _internal_video_status() const; + void _internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); public: - // .mavsdk.rpc.camera_server.CameraServerResult.Result result = 1; - void clear_result() ; - ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; - void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + // int32 image_count = 6; + void clear_image_count() ; + ::int32_t image_count() const; + void set_image_count(::int32_t value); private: - ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; - void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + ::int32_t _internal_image_count() const; + void _internal_set_image_count(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatus) private: class _Internal; @@ -4060,8 +5976,12 @@ class CameraServerResult final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; - int result_; + float image_interval_; + float recording_time_s_; + float available_capacity_; + int image_status_; + int video_status_; + ::int32_t image_count_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; @@ -4473,76 +6393,496 @@ inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { inline void StartVideoStreamingResponse::clear_stream_id() { _impl_.stream_id_ = 0; } -inline ::int32_t StartVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) - return _internal_stream_id(); +inline ::int32_t StartVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) + return _internal_stream_id(); +} +inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +} +inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeStopVideoStreamingRequest + +// ------------------------------------------------------------------- + +// StopVideoStreamingResponse + +// int32 stream_id = 1; +inline void StopVideoStreamingResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StopVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) + return _internal_stream_id(); +} +inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) +} +inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeSetModeRequest + +// ------------------------------------------------------------------- + +// SetModeResponse + +// .mavsdk.rpc.camera_server.Mode mode = 1; +inline void SetModeResponse::clear_mode() { + _impl_.mode_ = 0; +} +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::mode() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetModeResponse.mode) + return _internal_mode(); +} +inline void SetModeResponse::set_mode(::mavsdk::rpc::camera_server::Mode value) { + _internal_set_mode(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetModeResponse.mode) +} +inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::_internal_mode() const { + return static_cast<::mavsdk::rpc::camera_server::Mode>(_impl_.mode_); +} +inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mode value) { + ; + _impl_.mode_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeStorageInformationRequest + +// ------------------------------------------------------------------- + +// StorageInformationResponse + +// int32 storage_id = 1; +inline void StorageInformationResponse::clear_storage_id() { + _impl_.storage_id_ = 0; +} +inline ::int32_t StorageInformationResponse::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) + return _internal_storage_id(); +} +inline void StorageInformationResponse::set_storage_id(::int32_t value) { + _internal_set_storage_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformationResponse.storage_id) +} +inline ::int32_t StorageInformationResponse::_internal_storage_id() const { + return _impl_.storage_id_; +} +inline void StorageInformationResponse::_internal_set_storage_id(::int32_t value) { + ; + _impl_.storage_id_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStorageInformationRequest + +// .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; +inline bool RespondStorageInformationRequest::has_storage_information() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.storage_information_ != nullptr); + return value; +} +inline void RespondStorageInformationRequest::clear_storage_information() { + if (_impl_.storage_information_ != nullptr) _impl_.storage_information_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::StorageInformation& RespondStorageInformationRequest::_internal_storage_information() const { + const ::mavsdk::rpc::camera_server::StorageInformation* p = _impl_.storage_information_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_StorageInformation_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::StorageInformation& RespondStorageInformationRequest::storage_information() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + return _internal_storage_information(); +} +inline void RespondStorageInformationRequest::unsafe_arena_set_allocated_storage_information( + ::mavsdk::rpc::camera_server::StorageInformation* storage_information) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.storage_information_); + } + _impl_.storage_information_ = storage_information; + if (storage_information) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) +} +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::release_storage_information() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::StorageInformation* temp = _impl_.storage_information_; + _impl_.storage_information_ = 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::camera_server::StorageInformation* RespondStorageInformationRequest::unsafe_arena_release_storage_information() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::StorageInformation* temp = _impl_.storage_information_; + _impl_.storage_information_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::_internal_mutable_storage_information() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.storage_information_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::StorageInformation>(GetArenaForAllocation()); + _impl_.storage_information_ = p; + } + return _impl_.storage_information_; +} +inline ::mavsdk::rpc::camera_server::StorageInformation* RespondStorageInformationRequest::mutable_storage_information() { + ::mavsdk::rpc::camera_server::StorageInformation* _msg = _internal_mutable_storage_information(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) + return _msg; +} +inline void RespondStorageInformationRequest::set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* storage_information) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.storage_information_; + } + if (storage_information) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(storage_information); + if (message_arena != submessage_arena) { + storage_information = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, storage_information, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.storage_information_ = storage_information; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information) +} + +// ------------------------------------------------------------------- + +// RespondStorageInformationResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondStorageInformationResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void RespondStorageInformationResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStorageInformationResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStorageInformationResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void RespondStorageInformationResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* RespondStorageInformationResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStorageInformationResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) + return _msg; +} +inline void RespondStorageInformationResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStorageInformationResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SubscribeCaptureStatusRequest + +// ------------------------------------------------------------------- + +// CaptureStatusResponse + +// int32 reserved = 1; +inline void CaptureStatusResponse::clear_reserved() { + _impl_.reserved_ = 0; +} +inline ::int32_t CaptureStatusResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) + return _internal_reserved(); +} +inline void CaptureStatusResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatusResponse.reserved) +} +inline ::int32_t CaptureStatusResponse::_internal_reserved() const { + return _impl_.reserved_; +} +inline void CaptureStatusResponse::_internal_set_reserved(::int32_t value) { + ; + _impl_.reserved_ = value; +} + +// ------------------------------------------------------------------- + +// RespondCaptureStatusRequest + +// .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; +inline bool RespondCaptureStatusRequest::has_capture_status() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.capture_status_ != nullptr); + return value; +} +inline void RespondCaptureStatusRequest::clear_capture_status() { + if (_impl_.capture_status_ != nullptr) _impl_.capture_status_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CaptureStatus& RespondCaptureStatusRequest::_internal_capture_status() const { + const ::mavsdk::rpc::camera_server::CaptureStatus* p = _impl_.capture_status_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CaptureStatus_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CaptureStatus& RespondCaptureStatusRequest::capture_status() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + return _internal_capture_status(); +} +inline void RespondCaptureStatusRequest::unsafe_arena_set_allocated_capture_status( + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.capture_status_); + } + _impl_.capture_status_ = capture_status; + if (capture_status) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) +} +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::release_capture_status() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureStatus* temp = _impl_.capture_status_; + _impl_.capture_status_ = 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::camera_server::CaptureStatus* RespondCaptureStatusRequest::unsafe_arena_release_capture_status() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureStatus* temp = _impl_.capture_status_; + _impl_.capture_status_ = nullptr; + return temp; } -inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::_internal_mutable_capture_status() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.capture_status_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatus>(GetArenaForAllocation()); + _impl_.capture_status_ = p; + } + return _impl_.capture_status_; } -inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { - return _impl_.stream_id_; +inline ::mavsdk::rpc::camera_server::CaptureStatus* RespondCaptureStatusRequest::mutable_capture_status() { + ::mavsdk::rpc::camera_server::CaptureStatus* _msg = _internal_mutable_capture_status(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) + return _msg; } -inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; +inline void RespondCaptureStatusRequest::set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* capture_status) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.capture_status_; + } + if (capture_status) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(capture_status); + if (message_arena != submessage_arena) { + capture_status = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, capture_status, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.capture_status_ = capture_status; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status) } // ------------------------------------------------------------------- -// SubscribeStopVideoStreamingRequest - -// ------------------------------------------------------------------- - -// StopVideoStreamingResponse +// RespondCaptureStatusResponse -// int32 stream_id = 1; -inline void StopVideoStreamingResponse::clear_stream_id() { - _impl_.stream_id_ = 0; +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondCaptureStatusResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; } -inline ::int32_t StopVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) - return _internal_stream_id(); +inline void RespondCaptureStatusResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; } -inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondCaptureStatusResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { - return _impl_.stream_id_; +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondCaptureStatusResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; +inline void RespondCaptureStatusResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) } - -// ------------------------------------------------------------------- - -// SubscribeSetModeRequest - -// ------------------------------------------------------------------- - -// SetModeResponse - -// .mavsdk.rpc.camera_server.Mode mode = 1; -inline void SetModeResponse::clear_mode() { - _impl_.mode_ = 0; +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::Mode SetModeResponse::mode() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetModeResponse.mode) - return _internal_mode(); +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; } -inline void SetModeResponse::set_mode(::mavsdk::rpc::camera_server::Mode value) { - _internal_set_mode(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetModeResponse.mode) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::Mode SetModeResponse::_internal_mode() const { - return static_cast<::mavsdk::rpc::camera_server::Mode>(_impl_.mode_); +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondCaptureStatusResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) + return _msg; } -inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mode value) { - ; - _impl_.mode_ = value; +inline void RespondCaptureStatusResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondCaptureStatusResponse.camera_server_result) } // ------------------------------------------------------------------- @@ -5603,6 +7943,294 @@ inline void CameraServerResult::set_allocated_result_str(std::string* value) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.CameraServerResult.result_str) } +// ------------------------------------------------------------------- + +// StorageInformation + +// float used_storage_mib = 1; +inline void StorageInformation::clear_used_storage_mib() { + _impl_.used_storage_mib_ = 0; +} +inline float StorageInformation::used_storage_mib() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.used_storage_mib) + return _internal_used_storage_mib(); +} +inline void StorageInformation::set_used_storage_mib(float value) { + _internal_set_used_storage_mib(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.used_storage_mib) +} +inline float StorageInformation::_internal_used_storage_mib() const { + return _impl_.used_storage_mib_; +} +inline void StorageInformation::_internal_set_used_storage_mib(float value) { + ; + _impl_.used_storage_mib_ = value; +} + +// float available_storage_mib = 2; +inline void StorageInformation::clear_available_storage_mib() { + _impl_.available_storage_mib_ = 0; +} +inline float StorageInformation::available_storage_mib() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.available_storage_mib) + return _internal_available_storage_mib(); +} +inline void StorageInformation::set_available_storage_mib(float value) { + _internal_set_available_storage_mib(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.available_storage_mib) +} +inline float StorageInformation::_internal_available_storage_mib() const { + return _impl_.available_storage_mib_; +} +inline void StorageInformation::_internal_set_available_storage_mib(float value) { + ; + _impl_.available_storage_mib_ = value; +} + +// float total_storage_mib = 3; +inline void StorageInformation::clear_total_storage_mib() { + _impl_.total_storage_mib_ = 0; +} +inline float StorageInformation::total_storage_mib() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.total_storage_mib) + return _internal_total_storage_mib(); +} +inline void StorageInformation::set_total_storage_mib(float value) { + _internal_set_total_storage_mib(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.total_storage_mib) +} +inline float StorageInformation::_internal_total_storage_mib() const { + return _impl_.total_storage_mib_; +} +inline void StorageInformation::_internal_set_total_storage_mib(float value) { + ; + _impl_.total_storage_mib_ = value; +} + +// .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; +inline void StorageInformation::clear_storage_status() { + _impl_.storage_status_ = 0; +} +inline ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus StorageInformation::storage_status() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.storage_status) + return _internal_storage_status(); +} +inline void StorageInformation::set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value) { + _internal_set_storage_status(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.storage_status) +} +inline ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus StorageInformation::_internal_storage_status() const { + return static_cast<::mavsdk::rpc::camera_server::StorageInformation_StorageStatus>(_impl_.storage_status_); +} +inline void StorageInformation::_internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value) { + ; + _impl_.storage_status_ = value; +} + +// uint32 storage_id = 5; +inline void StorageInformation::clear_storage_id() { + _impl_.storage_id_ = 0u; +} +inline ::uint32_t StorageInformation::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.storage_id) + return _internal_storage_id(); +} +inline void StorageInformation::set_storage_id(::uint32_t value) { + _internal_set_storage_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.storage_id) +} +inline ::uint32_t StorageInformation::_internal_storage_id() const { + return _impl_.storage_id_; +} +inline void StorageInformation::_internal_set_storage_id(::uint32_t value) { + ; + _impl_.storage_id_ = value; +} + +// .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; +inline void StorageInformation::clear_storage_type() { + _impl_.storage_type_ = 0; +} +inline ::mavsdk::rpc::camera_server::StorageInformation_StorageType StorageInformation::storage_type() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.storage_type) + return _internal_storage_type(); +} +inline void StorageInformation::set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value) { + _internal_set_storage_type(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.storage_type) +} +inline ::mavsdk::rpc::camera_server::StorageInformation_StorageType StorageInformation::_internal_storage_type() const { + return static_cast<::mavsdk::rpc::camera_server::StorageInformation_StorageType>(_impl_.storage_type_); +} +inline void StorageInformation::_internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value) { + ; + _impl_.storage_type_ = value; +} + +// float read_speed = 7; +inline void StorageInformation::clear_read_speed() { + _impl_.read_speed_ = 0; +} +inline float StorageInformation::read_speed() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.read_speed) + return _internal_read_speed(); +} +inline void StorageInformation::set_read_speed(float value) { + _internal_set_read_speed(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.read_speed) +} +inline float StorageInformation::_internal_read_speed() const { + return _impl_.read_speed_; +} +inline void StorageInformation::_internal_set_read_speed(float value) { + ; + _impl_.read_speed_ = value; +} + +// float write_speed = 8; +inline void StorageInformation::clear_write_speed() { + _impl_.write_speed_ = 0; +} +inline float StorageInformation::write_speed() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.write_speed) + return _internal_write_speed(); +} +inline void StorageInformation::set_write_speed(float value) { + _internal_set_write_speed(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.write_speed) +} +inline float StorageInformation::_internal_write_speed() const { + return _impl_.write_speed_; +} +inline void StorageInformation::_internal_set_write_speed(float value) { + ; + _impl_.write_speed_ = value; +} + +// ------------------------------------------------------------------- + +// CaptureStatus + +// float image_interval = 1; +inline void CaptureStatus::clear_image_interval() { + _impl_.image_interval_ = 0; +} +inline float CaptureStatus::image_interval() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.image_interval) + return _internal_image_interval(); +} +inline void CaptureStatus::set_image_interval(float value) { + _internal_set_image_interval(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.image_interval) +} +inline float CaptureStatus::_internal_image_interval() const { + return _impl_.image_interval_; +} +inline void CaptureStatus::_internal_set_image_interval(float value) { + ; + _impl_.image_interval_ = value; +} + +// float recording_time_s = 2; +inline void CaptureStatus::clear_recording_time_s() { + _impl_.recording_time_s_ = 0; +} +inline float CaptureStatus::recording_time_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.recording_time_s) + return _internal_recording_time_s(); +} +inline void CaptureStatus::set_recording_time_s(float value) { + _internal_set_recording_time_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.recording_time_s) +} +inline float CaptureStatus::_internal_recording_time_s() const { + return _impl_.recording_time_s_; +} +inline void CaptureStatus::_internal_set_recording_time_s(float value) { + ; + _impl_.recording_time_s_ = value; +} + +// float available_capacity = 3; +inline void CaptureStatus::clear_available_capacity() { + _impl_.available_capacity_ = 0; +} +inline float CaptureStatus::available_capacity() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.available_capacity) + return _internal_available_capacity(); +} +inline void CaptureStatus::set_available_capacity(float value) { + _internal_set_available_capacity(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.available_capacity) +} +inline float CaptureStatus::_internal_available_capacity() const { + return _impl_.available_capacity_; +} +inline void CaptureStatus::_internal_set_available_capacity(float value) { + ; + _impl_.available_capacity_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; +inline void CaptureStatus::clear_image_status() { + _impl_.image_status_ = 0; +} +inline ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus CaptureStatus::image_status() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.image_status) + return _internal_image_status(); +} +inline void CaptureStatus::set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value) { + _internal_set_image_status(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.image_status) +} +inline ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus CaptureStatus::_internal_image_status() const { + return static_cast<::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus>(_impl_.image_status_); +} +inline void CaptureStatus::_internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value) { + ; + _impl_.image_status_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; +inline void CaptureStatus::clear_video_status() { + _impl_.video_status_ = 0; +} +inline ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus CaptureStatus::video_status() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.video_status) + return _internal_video_status(); +} +inline void CaptureStatus::set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value) { + _internal_set_video_status(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.video_status) +} +inline ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus CaptureStatus::_internal_video_status() const { + return static_cast<::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus>(_impl_.video_status_); +} +inline void CaptureStatus::_internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value) { + ; + _impl_.video_status_ = value; +} + +// int32 image_count = 6; +inline void CaptureStatus::clear_image_count() { + _impl_.image_count_ = 0; +} +inline ::int32_t CaptureStatus::image_count() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.image_count) + return _internal_image_count(); +} +inline void CaptureStatus::set_image_count(::int32_t value) { + _internal_set_image_count(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.image_count) +} +inline ::int32_t CaptureStatus::_internal_image_count() const { + return _impl_.image_count_; +} +inline void CaptureStatus::_internal_set_image_count(::int32_t value) { + ; + _impl_.image_count_ = value; +} + #ifdef __GNUC__ #pragma GCC diagnostic pop #endif // __GNUC__ @@ -5622,6 +8250,30 @@ inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::Cam return ::mavsdk::rpc::camera_server::CameraServerResult_Result_descriptor(); } template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::StorageInformation_StorageStatus> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::StorageInformation_StorageStatus>() { + return ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::StorageInformation_StorageType> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::StorageInformation_StorageType>() { + return ::mavsdk::rpc::camera_server::StorageInformation_StorageType_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus>() { + return ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus_descriptor(); +} +template <> +struct is_proto_enum<::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus> : std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus>() { + return ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus_descriptor(); +} +template <> struct is_proto_enum<::mavsdk::rpc::camera_server::TakePhotoFeedback> : std::true_type {}; template <> inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::TakePhotoFeedback>() { diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 05ffceaf43..43f5ba78d2 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -333,6 +333,248 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } } + static rpc::camera_server::StorageInformation::StorageStatus translateToRpcStorageStatus( + const mavsdk::CameraServer::StorageInformation::StorageStatus& storage_status) + { + switch (storage_status) { + default: + LogErr() << "Unknown storage_status enum value: " + << static_cast(storage_status); + // FALLTHROUGH + case mavsdk::CameraServer::StorageInformation::StorageStatus::NotAvailable: + return rpc::camera_server:: + StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; + case mavsdk::CameraServer::StorageInformation::StorageStatus::Unformatted: + return rpc::camera_server:: + StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; + case mavsdk::CameraServer::StorageInformation::StorageStatus::Formatted: + return rpc::camera_server:: + StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; + case mavsdk::CameraServer::StorageInformation::StorageStatus::NotSupported: + return rpc::camera_server:: + StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; + } + } + + static mavsdk::CameraServer::StorageInformation::StorageStatus translateFromRpcStorageStatus( + const rpc::camera_server::StorageInformation::StorageStatus storage_status) + { + switch (storage_status) { + default: + LogErr() << "Unknown storage_status enum value: " + << static_cast(storage_status); + // FALLTHROUGH + case rpc::camera_server::StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE: + return mavsdk::CameraServer::StorageInformation::StorageStatus::NotAvailable; + case rpc::camera_server::StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED: + return mavsdk::CameraServer::StorageInformation::StorageStatus::Unformatted; + case rpc::camera_server::StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED: + return mavsdk::CameraServer::StorageInformation::StorageStatus::Formatted; + case rpc::camera_server::StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED: + return mavsdk::CameraServer::StorageInformation::StorageStatus::NotSupported; + } + } + + static rpc::camera_server::StorageInformation::StorageType translateToRpcStorageType( + const mavsdk::CameraServer::StorageInformation::StorageType& storage_type) + { + switch (storage_type) { + default: + LogErr() << "Unknown storage_type enum value: " << static_cast(storage_type); + // FALLTHROUGH + case mavsdk::CameraServer::StorageInformation::StorageType::Unknown: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; + case mavsdk::CameraServer::StorageInformation::StorageType::UsbStick: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; + case mavsdk::CameraServer::StorageInformation::StorageType::Sd: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_SD; + case mavsdk::CameraServer::StorageInformation::StorageType::Microsd: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_MICROSD; + case mavsdk::CameraServer::StorageInformation::StorageType::Hd: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_HD; + case mavsdk::CameraServer::StorageInformation::StorageType::Other: + return rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_OTHER; + } + } + + static mavsdk::CameraServer::StorageInformation::StorageType translateFromRpcStorageType( + const rpc::camera_server::StorageInformation::StorageType storage_type) + { + switch (storage_type) { + default: + LogErr() << "Unknown storage_type enum value: " << static_cast(storage_type); + // FALLTHROUGH + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN: + return mavsdk::CameraServer::StorageInformation::StorageType::Unknown; + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_USB_STICK: + return mavsdk::CameraServer::StorageInformation::StorageType::UsbStick; + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_SD: + return mavsdk::CameraServer::StorageInformation::StorageType::Sd; + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_MICROSD: + return mavsdk::CameraServer::StorageInformation::StorageType::Microsd; + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_HD: + return mavsdk::CameraServer::StorageInformation::StorageType::Hd; + case rpc::camera_server::StorageInformation_StorageType_STORAGE_TYPE_OTHER: + return mavsdk::CameraServer::StorageInformation::StorageType::Other; + } + } + + static std::unique_ptr translateToRpcStorageInformation( + const mavsdk::CameraServer::StorageInformation& storage_information) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_used_storage_mib(storage_information.used_storage_mib); + + rpc_obj->set_available_storage_mib(storage_information.available_storage_mib); + + rpc_obj->set_total_storage_mib(storage_information.total_storage_mib); + + rpc_obj->set_storage_status( + translateToRpcStorageStatus(storage_information.storage_status)); + + rpc_obj->set_storage_id(storage_information.storage_id); + + rpc_obj->set_storage_type(translateToRpcStorageType(storage_information.storage_type)); + + rpc_obj->set_read_speed(storage_information.read_speed); + + rpc_obj->set_write_speed(storage_information.write_speed); + + return rpc_obj; + } + + static mavsdk::CameraServer::StorageInformation translateFromRpcStorageInformation( + const rpc::camera_server::StorageInformation& storage_information) + { + mavsdk::CameraServer::StorageInformation obj; + + obj.used_storage_mib = storage_information.used_storage_mib(); + + obj.available_storage_mib = storage_information.available_storage_mib(); + + obj.total_storage_mib = storage_information.total_storage_mib(); + + obj.storage_status = translateFromRpcStorageStatus(storage_information.storage_status()); + + obj.storage_id = storage_information.storage_id(); + + obj.storage_type = translateFromRpcStorageType(storage_information.storage_type()); + + obj.read_speed = storage_information.read_speed(); + + obj.write_speed = storage_information.write_speed(); + + return obj; + } + + static rpc::camera_server::CaptureStatus::ImageStatus + translateToRpcImageStatus(const mavsdk::CameraServer::CaptureStatus::ImageStatus& image_status) + { + switch (image_status) { + default: + LogErr() << "Unknown image_status enum value: " << static_cast(image_status); + // FALLTHROUGH + case mavsdk::CameraServer::CaptureStatus::ImageStatus::Idle: + return rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; + case mavsdk::CameraServer::CaptureStatus::ImageStatus::CaptureInProgress: + return rpc::camera_server:: + CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; + case mavsdk::CameraServer::CaptureStatus::ImageStatus::IntervalIdle: + return rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; + case mavsdk::CameraServer::CaptureStatus::ImageStatus::IntervalInProgress: + return rpc::camera_server:: + CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; + } + } + + static mavsdk::CameraServer::CaptureStatus::ImageStatus + translateFromRpcImageStatus(const rpc::camera_server::CaptureStatus::ImageStatus image_status) + { + switch (image_status) { + default: + LogErr() << "Unknown image_status enum value: " << static_cast(image_status); + // FALLTHROUGH + case rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE: + return mavsdk::CameraServer::CaptureStatus::ImageStatus::Idle; + case rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS: + return mavsdk::CameraServer::CaptureStatus::ImageStatus::CaptureInProgress; + case rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE: + return mavsdk::CameraServer::CaptureStatus::ImageStatus::IntervalIdle; + case rpc::camera_server::CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS: + return mavsdk::CameraServer::CaptureStatus::ImageStatus::IntervalInProgress; + } + } + + static rpc::camera_server::CaptureStatus::VideoStatus + translateToRpcVideoStatus(const mavsdk::CameraServer::CaptureStatus::VideoStatus& video_status) + { + switch (video_status) { + default: + LogErr() << "Unknown video_status enum value: " << static_cast(video_status); + // FALLTHROUGH + case mavsdk::CameraServer::CaptureStatus::VideoStatus::Idle: + return rpc::camera_server::CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; + case mavsdk::CameraServer::CaptureStatus::VideoStatus::CaptureInProgress: + return rpc::camera_server:: + CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; + } + } + + static mavsdk::CameraServer::CaptureStatus::VideoStatus + translateFromRpcVideoStatus(const rpc::camera_server::CaptureStatus::VideoStatus video_status) + { + switch (video_status) { + default: + LogErr() << "Unknown video_status enum value: " << static_cast(video_status); + // FALLTHROUGH + case rpc::camera_server::CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE: + return mavsdk::CameraServer::CaptureStatus::VideoStatus::Idle; + case rpc::camera_server::CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS: + return mavsdk::CameraServer::CaptureStatus::VideoStatus::CaptureInProgress; + } + } + + static std::unique_ptr + translateToRpcCaptureStatus(const mavsdk::CameraServer::CaptureStatus& capture_status) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_image_interval(capture_status.image_interval); + + rpc_obj->set_recording_time_s(capture_status.recording_time_s); + + rpc_obj->set_available_capacity(capture_status.available_capacity); + + rpc_obj->set_image_status(translateToRpcImageStatus(capture_status.image_status)); + + rpc_obj->set_video_status(translateToRpcVideoStatus(capture_status.video_status)); + + rpc_obj->set_image_count(capture_status.image_count); + + return rpc_obj; + } + + static mavsdk::CameraServer::CaptureStatus + translateFromRpcCaptureStatus(const rpc::camera_server::CaptureStatus& capture_status) + { + mavsdk::CameraServer::CaptureStatus obj; + + obj.image_interval = capture_status.image_interval(); + + obj.recording_time_s = capture_status.recording_time_s(); + + obj.available_capacity = capture_status.available_capacity(); + + obj.image_status = translateFromRpcImageStatus(capture_status.image_status()); + + obj.video_status = translateFromRpcVideoStatus(capture_status.video_status()); + + obj.image_count = capture_status.image_count(); + + return obj; + } + grpc::Status SetInformation( grpc::ServerContext* /* context */, const rpc::camera_server::SetInformationRequest* request, @@ -672,6 +914,150 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeStorageInformation( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::StorageInformationHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_storage_information( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t storage_information) { + rpc::camera_server::StorageInformationResponse rpc_response; + + rpc_response.set_storage_id(storage_information); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_storage_information(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondStorageInformation( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondStorageInformationRequest* request, + rpc::camera_server::RespondStorageInformationResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondStorageInformation sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_storage_information( + translateFromRpcStorageInformation(request->storage_information())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status SubscribeCaptureStatus( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::CaptureStatusHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_capture_status( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t capture_status) { + rpc::camera_server::CaptureStatusResponse rpc_response; + + rpc_response.set_reserved(capture_status); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_capture_status(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status RespondCaptureStatus( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondCaptureStatusRequest* request, + rpc::camera_server::RespondCaptureStatusResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondCaptureStatus sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_capture_status( + translateFromRpcCaptureStatus(request->capture_status())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); From 0a2bfd4804371cbd45801592f76263af3612c578 Mon Sep 17 00:00:00 2001 From: tbago Date: Sun, 18 Jun 2023 11:56:45 +0800 Subject: [PATCH 05/25] add unit on image interval and available capacity --- .../plugins/camera_server/camera_server.cpp | 12 +- .../camera_server/camera_server_impl.cpp | 4 +- .../plugins/camera_server/camera_server.h | 4 +- .../camera_server/camera_server.pb.cc | 226 +++++++++--------- .../camera_server/camera_server.pb.h | 84 +++---- .../camera_server_service_impl.h | 8 +- 6 files changed, 170 insertions(+), 168 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 30d1cc7838..eeb06deb61 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -367,12 +367,12 @@ operator<<(std::ostream& str, CameraServer::CaptureStatus::VideoStatus const& vi } bool operator==(const CameraServer::CaptureStatus& lhs, const CameraServer::CaptureStatus& rhs) { - return ((std::isnan(rhs.image_interval) && std::isnan(lhs.image_interval)) || - rhs.image_interval == lhs.image_interval) && + return ((std::isnan(rhs.image_interval_s) && std::isnan(lhs.image_interval_s)) || + rhs.image_interval_s == lhs.image_interval_s) && ((std::isnan(rhs.recording_time_s) && std::isnan(lhs.recording_time_s)) || rhs.recording_time_s == lhs.recording_time_s) && - ((std::isnan(rhs.available_capacity) && std::isnan(lhs.available_capacity)) || - rhs.available_capacity == lhs.available_capacity) && + ((std::isnan(rhs.available_capacity_mib) && std::isnan(lhs.available_capacity_mib)) || + rhs.available_capacity_mib == lhs.available_capacity_mib) && (rhs.image_status == lhs.image_status) && (rhs.video_status == lhs.video_status) && (rhs.image_count == lhs.image_count); } @@ -381,9 +381,9 @@ std::ostream& operator<<(std::ostream& str, CameraServer::CaptureStatus const& c { str << std::setprecision(15); str << "capture_status:" << '\n' << "{\n"; - str << " image_interval: " << capture_status.image_interval << '\n'; + str << " image_interval_s: " << capture_status.image_interval_s << '\n'; str << " recording_time_s: " << capture_status.recording_time_s << '\n'; - str << " available_capacity: " << capture_status.available_capacity << '\n'; + str << " available_capacity_mib: " << capture_status.available_capacity_mib << '\n'; str << " image_status: " << capture_status.image_status << '\n'; str << " video_status: " << capture_status.video_status << '\n'; str << " image_count: " << capture_status.image_count << '\n'; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 2baba09bc3..32ba7d41d3 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -476,8 +476,10 @@ CameraServerImpl::respond_capture_status(CameraServer::CaptureStatus capture_sta } const uint32_t recording_time_ms = static_cast(static_cast(capture_status.recording_time_s) * 1e3); - const float available_capacity = capture_status.available_capacity; + const float available_capacity = capture_status.available_capacity_mib; + // FIXME for now the image catpure interval is the interval state of the camera server + // so the capture_status.image_interval_s is useless for now _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message{}; mavlink_msg_camera_capture_status_pack_chan( diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index e1b3356bf0..599d810f4a 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -330,9 +330,9 @@ class CameraServer : public ServerPluginBase { friend std::ostream& operator<<(std::ostream& str, CameraServer::CaptureStatus::VideoStatus const& video_status); - float image_interval{}; /**< @brief Image capture interval (in s) */ + float image_interval_s{}; /**< @brief Image capture interval (in s) */ float recording_time_s{}; /**< @brief Elapsed time since recording started (in s) */ - float available_capacity{}; /**< @brief Available storage capacity. (in MiB) */ + float available_capacity_mib{}; /**< @brief Available storage capacity. (in MiB) */ ImageStatus image_status{}; /**< @brief Current status of image capturing */ VideoStatus video_status{}; /**< @brief Current status of video capturing */ int32_t image_count{}; /**< @brief Total number of images captured ('forever', or until diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index a9b18986f3..83c3e7f800 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -583,11 +583,11 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT template PROTOBUF_CONSTEXPR CaptureStatus::CaptureStatus( ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_.image_interval_)*/ 0 + /*decltype(_impl_.image_interval_s_)*/ 0 , /*decltype(_impl_.recording_time_s_)*/ 0 - , /*decltype(_impl_.available_capacity_)*/ 0 + , /*decltype(_impl_.available_capacity_mib_)*/ 0 , /*decltype(_impl_.image_status_)*/ 0 @@ -949,9 +949,9 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_interval_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_interval_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.recording_time_s_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.available_capacity_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.available_capacity_mib_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_status_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.video_status_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _impl_.image_count_), @@ -1115,71 +1115,71 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "OWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STO" "RAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003" "\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OT" - "HER\020\376\001\"\350\003\n\rCaptureStatus\022\026\n\016image_interv" - "al\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\032\n\022av" - "ailable_capacity\030\003 \001(\002\022I\n\014image_status\030\004" - " \001(\01623.mavsdk.rpc.camera_server.CaptureS" - "tatus.ImageStatus\022I\n\014video_status\030\005 \001(\0162" - "3.mavsdk.rpc.camera_server.CaptureStatus" - ".VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013Im" - "ageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMAG" - "E_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE_" - "STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_I" - "NTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n\021" - "VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAPT" - "URE_IN_PROGRESS\020\001*\216\001\n\021TakePhotoFeedback\022" - "\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032\n\026TAKE" - "_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO_FEEDB" - "ACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_FAILED" - "\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHO" - "TO\020\001\022\016\n\nMODE_VIDEO\020\0022\226\016\n\023CameraServerSer" - "vice\022y\n\016SetInformation\022/.mavsdk.rpc.came" - "ra_server.SetInformationRequest\0320.mavsdk" - ".rpc.camera_server.SetInformationRespons" - "e\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.ca" - "mera_server.SetInProgressRequest\032/.mavsd" - "k.rpc.camera_server.SetInProgressRespons" - "e\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.r" - "pc.camera_server.SubscribeTakePhotoReque" - "st\032+.mavsdk.rpc.camera_server.TakePhotoR" - "esponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.ma" - "vsdk.rpc.camera_server.RespondTakePhotoR" - "equest\0322.mavsdk.rpc.camera_server.Respon" - "dTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeSt" - "artVideo\0224.mavsdk.rpc.camera_server.Subs" - "cribeStartVideoRequest\032,.mavsdk.rpc.came" - "ra_server.StartVideoResponse\"\004\200\265\030\0000\001\022~\n\022" - "SubscribeStopVideo\0223.mavsdk.rpc.camera_s" - "erver.SubscribeStopVideoRequest\032+.mavsdk" - ".rpc.camera_server.StopVideoResponse\"\004\200\265" - "\030\0000\001\022\234\001\n\034SubscribeStartVideoStreaming\022=." - "mavsdk.rpc.camera_server.SubscribeStartV" - "ideoStreamingRequest\0325.mavsdk.rpc.camera" - "_server.StartVideoStreamingResponse\"\004\200\265\030" - "\0000\001\022\231\001\n\033SubscribeStopVideoStreaming\022<.ma" - "vsdk.rpc.camera_server.SubscribeStopVide" - "oStreamingRequest\0324.mavsdk.rpc.camera_se" - "rver.StopVideoStreamingResponse\"\004\200\265\030\0000\001\022" - "x\n\020SubscribeSetMode\0221.mavsdk.rpc.camera_" - "server.SubscribeSetModeRequest\032).mavsdk." - "rpc.camera_server.SetModeResponse\"\004\200\265\030\0000" - "\001\022\231\001\n\033SubscribeStorageInformation\022<.mavs" - "dk.rpc.camera_server.SubscribeStorageInf" - "ormationRequest\0324.mavsdk.rpc.camera_serv" - "er.StorageInformationResponse\"\004\200\265\030\0000\001\022\232\001" - "\n\031RespondStorageInformation\022:.mavsdk.rpc" - ".camera_server.RespondStorageInformation" - "Request\032;.mavsdk.rpc.camera_server.Respo" - "ndStorageInformationResponse\"\004\200\265\030\001\022\212\001\n\026S" - "ubscribeCaptureStatus\0227.mavsdk.rpc.camer" - "a_server.SubscribeCaptureStatusRequest\032/" - ".mavsdk.rpc.camera_server.CaptureStatusR" - "esponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondCaptureStatus" - "\0225.mavsdk.rpc.camera_server.RespondCaptu" - "reStatusRequest\0326.mavsdk.rpc.camera_serv" - "er.RespondCaptureStatusResponse\"\004\200\265\030\001B,\n" - "\027io.mavsdk.camera_serverB\021CameraServerPr" - "otob\006proto3" + "HER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020image_interv" + "al_s\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026" + "available_capacity_mib\030\003 \001(\002\022I\n\014image_st" + "atus\030\004 \001(\01623.mavsdk.rpc.camera_server.Ca" + "ptureStatus.ImageStatus\022I\n\014video_status\030" + "\005 \001(\01623.mavsdk.rpc.camera_server.Capture" + "Status.VideoStatus\022\023\n\013image_count\030\006 \001(\005\"" + "\221\001\n\013ImageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$" + "\n IMAGE_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032" + "IMAGE_STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_ST" + "ATUS_INTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStat" + "us\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATU" + "S_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021TakePhotoFee" + "dback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032" + "\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO" + "_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_" + "FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMO" + "DE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\226\016\n\023CameraSer" + "verService\022y\n\016SetInformation\022/.mavsdk.rp" + "c.camera_server.SetInformationRequest\0320." + "mavsdk.rpc.camera_server.SetInformationR" + "esponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk." + "rpc.camera_server.SetInProgressRequest\032/" + ".mavsdk.rpc.camera_server.SetInProgressR" + "esponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.ma" + "vsdk.rpc.camera_server.SubscribeTakePhot" + "oRequest\032+.mavsdk.rpc.camera_server.Take" + "PhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhot" + "o\0221.mavsdk.rpc.camera_server.RespondTake" + "PhotoRequest\0322.mavsdk.rpc.camera_server." + "RespondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023Subsc" + "ribeStartVideo\0224.mavsdk.rpc.camera_serve" + "r.SubscribeStartVideoRequest\032,.mavsdk.rp" + "c.camera_server.StartVideoResponse\"\004\200\265\030\000" + "0\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.ca" + "mera_server.SubscribeStopVideoRequest\032+." + "mavsdk.rpc.camera_server.StopVideoRespon" + "se\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideoStream" + "ing\022=.mavsdk.rpc.camera_server.Subscribe" + "StartVideoStreamingRequest\0325.mavsdk.rpc." + "camera_server.StartVideoStreamingRespons" + "e\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoStreamin" + "g\022<.mavsdk.rpc.camera_server.SubscribeSt" + "opVideoStreamingRequest\0324.mavsdk.rpc.cam" + "era_server.StopVideoStreamingResponse\"\004\200" + "\265\030\0000\001\022x\n\020SubscribeSetMode\0221.mavsdk.rpc.c" + "amera_server.SubscribeSetModeRequest\032).m" + "avsdk.rpc.camera_server.SetModeResponse\"" + "\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorageInformation\022" + "<.mavsdk.rpc.camera_server.SubscribeStor" + "ageInformationRequest\0324.mavsdk.rpc.camer" + "a_server.StorageInformationResponse\"\004\200\265\030" + "\0000\001\022\232\001\n\031RespondStorageInformation\022:.mavs" + "dk.rpc.camera_server.RespondStorageInfor" + "mationRequest\032;.mavsdk.rpc.camera_server" + ".RespondStorageInformationResponse\"\004\200\265\030\001" + "\022\212\001\n\026SubscribeCaptureStatus\0227.mavsdk.rpc" + ".camera_server.SubscribeCaptureStatusReq" + "uest\032/.mavsdk.rpc.camera_server.CaptureS" + "tatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondCapture" + "Status\0225.mavsdk.rpc.camera_server.Respon" + "dCaptureStatusRequest\0326.mavsdk.rpc.camer" + "a_server.RespondCaptureStatusResponse\"\004\200" + "\265\030\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" + "rverProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1189,7 +1189,7 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 5971, + 5977, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, @@ -7428,11 +7428,11 @@ CaptureStatus::CaptureStatus(const CaptureStatus& from) inline void CaptureStatus::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.image_interval_) { 0 } + decltype(_impl_.image_interval_s_) { 0 } , decltype(_impl_.recording_time_s_) { 0 } - , decltype(_impl_.available_capacity_) { 0 } + , decltype(_impl_.available_capacity_mib_) { 0 } , decltype(_impl_.image_status_) { 0 } @@ -7467,9 +7467,9 @@ void CaptureStatus::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.image_interval_, 0, static_cast<::size_t>( + ::memset(&_impl_.image_interval_s_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.image_count_) - - reinterpret_cast(&_impl_.image_interval_)) + sizeof(_impl_.image_count_)); + reinterpret_cast(&_impl_.image_interval_s_)) + sizeof(_impl_.image_count_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -7479,10 +7479,10 @@ const char* CaptureStatus::_InternalParse(const char* ptr, ::_pbi::ParseContext* ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // float image_interval = 1; + // float image_interval_s = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 13)) { - _impl_.image_interval_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + _impl_.image_interval_s_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; @@ -7497,10 +7497,10 @@ const char* CaptureStatus::_InternalParse(const char* ptr, ::_pbi::ParseContext* goto handle_unusual; } continue; - // float available_capacity = 3; + // float available_capacity_mib = 3; case 3: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 29)) { - _impl_.available_capacity_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + _impl_.available_capacity_mib_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; @@ -7564,15 +7564,15 @@ ::uint8_t* CaptureStatus::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // float image_interval = 1; + // float image_interval_s = 1; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_image_interval = this->_internal_image_interval(); - ::uint32_t raw_image_interval; - memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); - if (raw_image_interval != 0) { + float tmp_image_interval_s = this->_internal_image_interval_s(); + ::uint32_t raw_image_interval_s; + memcpy(&raw_image_interval_s, &tmp_image_interval_s, sizeof(tmp_image_interval_s)); + if (raw_image_interval_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_image_interval(), target); + 1, this->_internal_image_interval_s(), target); } // float recording_time_s = 2; @@ -7586,15 +7586,15 @@ ::uint8_t* CaptureStatus::_InternalSerialize( 2, this->_internal_recording_time_s(), target); } - // float available_capacity = 3; + // float available_capacity_mib = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_available_capacity = this->_internal_available_capacity(); - ::uint32_t raw_available_capacity; - memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); - if (raw_available_capacity != 0) { + float tmp_available_capacity_mib = this->_internal_available_capacity_mib(); + ::uint32_t raw_available_capacity_mib; + memcpy(&raw_available_capacity_mib, &tmp_available_capacity_mib, sizeof(tmp_available_capacity_mib)); + if (raw_available_capacity_mib != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_available_capacity(), target); + 3, this->_internal_available_capacity_mib(), target); } // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; @@ -7634,12 +7634,12 @@ ::size_t CaptureStatus::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float image_interval = 1; + // float image_interval_s = 1; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_image_interval = this->_internal_image_interval(); - ::uint32_t raw_image_interval; - memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); - if (raw_image_interval != 0) { + float tmp_image_interval_s = this->_internal_image_interval_s(); + ::uint32_t raw_image_interval_s; + memcpy(&raw_image_interval_s, &tmp_image_interval_s, sizeof(tmp_image_interval_s)); + if (raw_image_interval_s != 0) { total_size += 5; } @@ -7652,12 +7652,12 @@ ::size_t CaptureStatus::ByteSizeLong() const { total_size += 5; } - // float available_capacity = 3; + // float available_capacity_mib = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_available_capacity = this->_internal_available_capacity(); - ::uint32_t raw_available_capacity; - memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); - if (raw_available_capacity != 0) { + float tmp_available_capacity_mib = this->_internal_available_capacity_mib(); + ::uint32_t raw_available_capacity_mib; + memcpy(&raw_available_capacity_mib, &tmp_available_capacity_mib, sizeof(tmp_available_capacity_mib)); + if (raw_available_capacity_mib != 0) { total_size += 5; } @@ -7698,11 +7698,11 @@ void CaptureStatus::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const :: (void) cached_has_bits; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_image_interval = from._internal_image_interval(); - ::uint32_t raw_image_interval; - memcpy(&raw_image_interval, &tmp_image_interval, sizeof(tmp_image_interval)); - if (raw_image_interval != 0) { - _this->_internal_set_image_interval(from._internal_image_interval()); + float tmp_image_interval_s = from._internal_image_interval_s(); + ::uint32_t raw_image_interval_s; + memcpy(&raw_image_interval_s, &tmp_image_interval_s, sizeof(tmp_image_interval_s)); + if (raw_image_interval_s != 0) { + _this->_internal_set_image_interval_s(from._internal_image_interval_s()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_recording_time_s = from._internal_recording_time_s(); @@ -7712,11 +7712,11 @@ void CaptureStatus::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const :: _this->_internal_set_recording_time_s(from._internal_recording_time_s()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_available_capacity = from._internal_available_capacity(); - ::uint32_t raw_available_capacity; - memcpy(&raw_available_capacity, &tmp_available_capacity, sizeof(tmp_available_capacity)); - if (raw_available_capacity != 0) { - _this->_internal_set_available_capacity(from._internal_available_capacity()); + float tmp_available_capacity_mib = from._internal_available_capacity_mib(); + ::uint32_t raw_available_capacity_mib; + memcpy(&raw_available_capacity_mib, &tmp_available_capacity_mib, sizeof(tmp_available_capacity_mib)); + if (raw_available_capacity_mib != 0) { + _this->_internal_set_available_capacity_mib(from._internal_available_capacity_mib()); } if (from._internal_image_status() != 0) { _this->_internal_set_image_status(from._internal_image_status()); @@ -7747,9 +7747,9 @@ void CaptureStatus::InternalSwap(CaptureStatus* other) { ::PROTOBUF_NAMESPACE_ID::internal::memswap< PROTOBUF_FIELD_OFFSET(CaptureStatus, _impl_.image_count_) + sizeof(CaptureStatus::_impl_.image_count_) - - PROTOBUF_FIELD_OFFSET(CaptureStatus, _impl_.image_interval_)>( - reinterpret_cast(&_impl_.image_interval_), - reinterpret_cast(&other->_impl_.image_interval_)); + - PROTOBUF_FIELD_OFFSET(CaptureStatus, _impl_.image_interval_s_)>( + reinterpret_cast(&_impl_.image_interval_s_), + reinterpret_cast(&other->_impl_.image_interval_s_)); } ::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatus::GetMetadata() const { diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 6d51d6c038..c806ed898e 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -5901,21 +5901,21 @@ class CaptureStatus final : // accessors ------------------------------------------------------- enum : int { - kImageIntervalFieldNumber = 1, + kImageIntervalSFieldNumber = 1, kRecordingTimeSFieldNumber = 2, - kAvailableCapacityFieldNumber = 3, + kAvailableCapacityMibFieldNumber = 3, kImageStatusFieldNumber = 4, kVideoStatusFieldNumber = 5, kImageCountFieldNumber = 6, }; - // float image_interval = 1; - void clear_image_interval() ; - float image_interval() const; - void set_image_interval(float value); + // float image_interval_s = 1; + void clear_image_interval_s() ; + float image_interval_s() const; + void set_image_interval_s(float value); private: - float _internal_image_interval() const; - void _internal_set_image_interval(float value); + float _internal_image_interval_s() const; + void _internal_set_image_interval_s(float value); public: // float recording_time_s = 2; @@ -5928,14 +5928,14 @@ class CaptureStatus final : void _internal_set_recording_time_s(float value); public: - // float available_capacity = 3; - void clear_available_capacity() ; - float available_capacity() const; - void set_available_capacity(float value); + // float available_capacity_mib = 3; + void clear_available_capacity_mib() ; + float available_capacity_mib() const; + void set_available_capacity_mib(float value); private: - float _internal_available_capacity() const; - void _internal_set_available_capacity(float value); + float _internal_available_capacity_mib() const; + void _internal_set_available_capacity_mib(float value); public: // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; @@ -5976,9 +5976,9 @@ class CaptureStatus final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - float image_interval_; + float image_interval_s_; float recording_time_s_; - float available_capacity_; + float available_capacity_mib_; int image_status_; int video_status_; ::int32_t image_count_; @@ -8111,24 +8111,24 @@ inline void StorageInformation::_internal_set_write_speed(float value) { // CaptureStatus -// float image_interval = 1; -inline void CaptureStatus::clear_image_interval() { - _impl_.image_interval_ = 0; +// float image_interval_s = 1; +inline void CaptureStatus::clear_image_interval_s() { + _impl_.image_interval_s_ = 0; } -inline float CaptureStatus::image_interval() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.image_interval) - return _internal_image_interval(); +inline float CaptureStatus::image_interval_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.image_interval_s) + return _internal_image_interval_s(); } -inline void CaptureStatus::set_image_interval(float value) { - _internal_set_image_interval(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.image_interval) +inline void CaptureStatus::set_image_interval_s(float value) { + _internal_set_image_interval_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.image_interval_s) } -inline float CaptureStatus::_internal_image_interval() const { - return _impl_.image_interval_; +inline float CaptureStatus::_internal_image_interval_s() const { + return _impl_.image_interval_s_; } -inline void CaptureStatus::_internal_set_image_interval(float value) { +inline void CaptureStatus::_internal_set_image_interval_s(float value) { ; - _impl_.image_interval_ = value; + _impl_.image_interval_s_ = value; } // float recording_time_s = 2; @@ -8151,24 +8151,24 @@ inline void CaptureStatus::_internal_set_recording_time_s(float value) { _impl_.recording_time_s_ = value; } -// float available_capacity = 3; -inline void CaptureStatus::clear_available_capacity() { - _impl_.available_capacity_ = 0; +// float available_capacity_mib = 3; +inline void CaptureStatus::clear_available_capacity_mib() { + _impl_.available_capacity_mib_ = 0; } -inline float CaptureStatus::available_capacity() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.available_capacity) - return _internal_available_capacity(); +inline float CaptureStatus::available_capacity_mib() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.CaptureStatus.available_capacity_mib) + return _internal_available_capacity_mib(); } -inline void CaptureStatus::set_available_capacity(float value) { - _internal_set_available_capacity(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.available_capacity) +inline void CaptureStatus::set_available_capacity_mib(float value) { + _internal_set_available_capacity_mib(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.CaptureStatus.available_capacity_mib) } -inline float CaptureStatus::_internal_available_capacity() const { - return _impl_.available_capacity_; +inline float CaptureStatus::_internal_available_capacity_mib() const { + return _impl_.available_capacity_mib_; } -inline void CaptureStatus::_internal_set_available_capacity(float value) { +inline void CaptureStatus::_internal_set_available_capacity_mib(float value) { ; - _impl_.available_capacity_ = value; + _impl_.available_capacity_mib_ = value; } // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 43f5ba78d2..40912b71ea 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -540,11 +540,11 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer { auto rpc_obj = std::make_unique(); - rpc_obj->set_image_interval(capture_status.image_interval); + rpc_obj->set_image_interval_s(capture_status.image_interval_s); rpc_obj->set_recording_time_s(capture_status.recording_time_s); - rpc_obj->set_available_capacity(capture_status.available_capacity); + rpc_obj->set_available_capacity_mib(capture_status.available_capacity_mib); rpc_obj->set_image_status(translateToRpcImageStatus(capture_status.image_status)); @@ -560,11 +560,11 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer { mavsdk::CameraServer::CaptureStatus obj; - obj.image_interval = capture_status.image_interval(); + obj.image_interval_s = capture_status.image_interval_s(); obj.recording_time_s = capture_status.recording_time_s(); - obj.available_capacity = capture_status.available_capacity(); + obj.available_capacity_mib = capture_status.available_capacity_mib(); obj.image_status = translateFromRpcImageStatus(capture_status.image_status()); From 3086da3ca276a35d724d85bf949396080a2c377f Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 24 Jun 2023 07:37:13 +0800 Subject: [PATCH 06/25] storage information : add unit on read speed and write speed --- .../plugins/camera_server/camera_server.cpp | 12 +- .../camera_server/camera_server_impl.cpp | 4 +- .../plugins/camera_server/camera_server.h | 4 +- .../camera_server/camera_server.pb.cc | 244 +++++++++--------- .../camera_server/camera_server.pb.h | 84 +++--- .../camera_server_service_impl.h | 8 +- 6 files changed, 178 insertions(+), 178 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index eeb06deb61..8f26c2f099 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -313,10 +313,10 @@ bool operator==( rhs.total_storage_mib == lhs.total_storage_mib) && (rhs.storage_status == lhs.storage_status) && (rhs.storage_id == lhs.storage_id) && (rhs.storage_type == lhs.storage_type) && - ((std::isnan(rhs.read_speed) && std::isnan(lhs.read_speed)) || - rhs.read_speed == lhs.read_speed) && - ((std::isnan(rhs.write_speed) && std::isnan(lhs.write_speed)) || - rhs.write_speed == lhs.write_speed); + ((std::isnan(rhs.read_speed_mib_s) && std::isnan(lhs.read_speed_mib_s)) || + rhs.read_speed_mib_s == lhs.read_speed_mib_s) && + ((std::isnan(rhs.write_speed_mib_s) && std::isnan(lhs.write_speed_mib_s)) || + rhs.write_speed_mib_s == lhs.write_speed_mib_s); } std::ostream& @@ -330,8 +330,8 @@ operator<<(std::ostream& str, CameraServer::StorageInformation const& storage_in str << " storage_status: " << storage_information.storage_status << '\n'; str << " storage_id: " << storage_information.storage_id << '\n'; str << " storage_type: " << storage_information.storage_type << '\n'; - str << " read_speed: " << storage_information.read_speed << '\n'; - str << " write_speed: " << storage_information.write_speed << '\n'; + str << " read_speed_mib_s: " << storage_information.read_speed_mib_s << '\n'; + str << " write_speed_mib_s: " << storage_information.write_speed_mib_s << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 32ba7d41d3..cde1a81e8d 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -368,8 +368,8 @@ CameraServer::Result CameraServerImpl::respond_storage_information( const float total_capacity = storage_information.total_storage_mib; const float used_capacity = storage_information.used_storage_mib; const float available_capacity = storage_information.available_storage_mib; - const float read_speed = storage_information.read_speed; - const float write_speed = storage_information.write_speed; + const float read_speed = storage_information.read_speed_mib_s; + const float write_speed = storage_information.write_speed_mib_s; auto status = STORAGE_STATUS::STORAGE_STATUS_NOT_SUPPORTED; switch (storage_information.storage_status) { diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 599d810f4a..57fe06d30e 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -272,8 +272,8 @@ class CameraServer : public ServerPluginBase { StorageStatus storage_status{}; /**< @brief Storage status */ uint32_t storage_id{}; /**< @brief Storage ID starting at 1 */ StorageType storage_type{}; /**< @brief Storage type */ - float read_speed{}; /**< @brief Read speed [MiB/s] */ - float write_speed{}; /**< @brief Write speed [MiB/s] */ + float read_speed_mib_s{}; /**< @brief Read speed [MiB/s] */ + float write_speed_mib_s{}; /**< @brief Write speed [MiB/s] */ }; /** diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 83c3e7f800..88c28ad370 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -565,9 +565,9 @@ PROTOBUF_CONSTEXPR StorageInformation::StorageInformation( , /*decltype(_impl_.storage_type_)*/ 0 - , /*decltype(_impl_.read_speed_)*/ 0 + , /*decltype(_impl_.read_speed_mib_s_)*/ 0 - , /*decltype(_impl_.write_speed_)*/ 0 + , /*decltype(_impl_.write_speed_mib_s_)*/ 0 , /*decltype(_impl_._cached_size_)*/{}} {} struct StorageInformationDefaultTypeInternal { @@ -939,8 +939,8 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_status_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.storage_type_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.read_speed_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.write_speed_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.read_speed_mib_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformation, _impl_.write_speed_mib_s_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatus, _internal_metadata_), ~0u, // no _extensions_ @@ -1099,87 +1099,87 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" - "M\020\010\"\200\005\n\022StorageInformation\022\030\n\020used_stora" + "M\020\010\"\214\005\n\022StorageInformation\022\030\n\020used_stora" "ge_mib\030\001 \001(\002\022\035\n\025available_storage_mib\030\002 " "\001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016storag" "e_status\030\004 \001(\0162:.mavsdk.rpc.camera_serve" "r.StorageInformation.StorageStatus\022\022\n\nst" "orage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628.m" "avsdk.rpc.camera_server.StorageInformati" - "on.StorageType\022\022\n\nread_speed\030\007 \001(\002\022\023\n\013wr" - "ite_speed\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STO" - "RAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_S" - "TATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FO" - "RMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTE" - "D\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKN" - "OWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STO" - "RAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003" - "\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OT" - "HER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020image_interv" - "al_s\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026" - "available_capacity_mib\030\003 \001(\002\022I\n\014image_st" - "atus\030\004 \001(\01623.mavsdk.rpc.camera_server.Ca" - "ptureStatus.ImageStatus\022I\n\014video_status\030" - "\005 \001(\01623.mavsdk.rpc.camera_server.Capture" - "Status.VideoStatus\022\023\n\013image_count\030\006 \001(\005\"" - "\221\001\n\013ImageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$" - "\n IMAGE_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032" - "IMAGE_STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_ST" - "ATUS_INTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStat" - "us\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATU" - "S_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021TakePhotoFee" - "dback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNOWN\020\000\022\032" - "\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE_PHOTO" - "_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEEDBACK_" - "FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMO" - "DE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\226\016\n\023CameraSer" - "verService\022y\n\016SetInformation\022/.mavsdk.rp" - "c.camera_server.SetInformationRequest\0320." - "mavsdk.rpc.camera_server.SetInformationR" - "esponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk." - "rpc.camera_server.SetInProgressRequest\032/" - ".mavsdk.rpc.camera_server.SetInProgressR" - "esponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.ma" - "vsdk.rpc.camera_server.SubscribeTakePhot" - "oRequest\032+.mavsdk.rpc.camera_server.Take" - "PhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhot" - "o\0221.mavsdk.rpc.camera_server.RespondTake" - "PhotoRequest\0322.mavsdk.rpc.camera_server." - "RespondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023Subsc" - "ribeStartVideo\0224.mavsdk.rpc.camera_serve" - "r.SubscribeStartVideoRequest\032,.mavsdk.rp" - "c.camera_server.StartVideoResponse\"\004\200\265\030\000" - "0\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.ca" - "mera_server.SubscribeStopVideoRequest\032+." - "mavsdk.rpc.camera_server.StopVideoRespon" - "se\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideoStream" - "ing\022=.mavsdk.rpc.camera_server.Subscribe" - "StartVideoStreamingRequest\0325.mavsdk.rpc." - "camera_server.StartVideoStreamingRespons" - "e\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoStreamin" - "g\022<.mavsdk.rpc.camera_server.SubscribeSt" - "opVideoStreamingRequest\0324.mavsdk.rpc.cam" - "era_server.StopVideoStreamingResponse\"\004\200" - "\265\030\0000\001\022x\n\020SubscribeSetMode\0221.mavsdk.rpc.c" - "amera_server.SubscribeSetModeRequest\032).m" - "avsdk.rpc.camera_server.SetModeResponse\"" - "\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorageInformation\022" - "<.mavsdk.rpc.camera_server.SubscribeStor" - "ageInformationRequest\0324.mavsdk.rpc.camer" - "a_server.StorageInformationResponse\"\004\200\265\030" - "\0000\001\022\232\001\n\031RespondStorageInformation\022:.mavs" - "dk.rpc.camera_server.RespondStorageInfor" - "mationRequest\032;.mavsdk.rpc.camera_server" - ".RespondStorageInformationResponse\"\004\200\265\030\001" - "\022\212\001\n\026SubscribeCaptureStatus\0227.mavsdk.rpc" - ".camera_server.SubscribeCaptureStatusReq" - "uest\032/.mavsdk.rpc.camera_server.CaptureS" - "tatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondCapture" - "Status\0225.mavsdk.rpc.camera_server.Respon" - "dCaptureStatusRequest\0326.mavsdk.rpc.camer" - "a_server.RespondCaptureStatusResponse\"\004\200" - "\265\030\001B,\n\027io.mavsdk.camera_serverB\021CameraSe" - "rverProtob\006proto3" + "on.StorageType\022\030\n\020read_speed_mib_s\030\007 \001(\002" + "\022\031\n\021write_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorageS" + "tatus\022 \n\034STORAGE_STATUS_NOT_AVAILABLE\020\000\022" + "\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STORA" + "GE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STATUS_" + "NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STORA" + "GE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_ST" + "ICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TY" + "PE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STO" + "RAGE_TYPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020" + "image_interval_s\030\001 \001(\002\022\030\n\020recording_time" + "_s\030\002 \001(\002\022\036\n\026available_capacity_mib\030\003 \001(\002" + "\022I\n\014image_status\030\004 \001(\01623.mavsdk.rpc.came" + "ra_server.CaptureStatus.ImageStatus\022I\n\014v" + "ideo_status\030\005 \001(\01623.mavsdk.rpc.camera_se" + "rver.CaptureStatus.VideoStatus\022\023\n\013image_" + "count\030\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_STA" + "TUS_IDLE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_PR" + "OGRESS\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE\020\002" + "\022%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\020\003\"" + "J\n\013VideoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n" + " VIDEO_STATUS_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021" + "TakePhotoFeedback\022\037\n\033TAKE_PHOTO_FEEDBACK" + "_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034" + "\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHO" + "TO_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNK" + "NOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\226" + "\016\n\023CameraServerService\022y\n\016SetInformation" + "\022/.mavsdk.rpc.camera_server.SetInformati" + "onRequest\0320.mavsdk.rpc.camera_server.Set" + "InformationResponse\"\004\200\265\030\001\022v\n\rSetInProgre" + "ss\022..mavsdk.rpc.camera_server.SetInProgr" + "essRequest\032/.mavsdk.rpc.camera_server.Se" + "tInProgressResponse\"\004\200\265\030\001\022~\n\022SubscribeTa" + "kePhoto\0223.mavsdk.rpc.camera_server.Subsc" + "ribeTakePhotoRequest\032+.mavsdk.rpc.camera" + "_server.TakePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020Res" + "pondTakePhoto\0221.mavsdk.rpc.camera_server" + ".RespondTakePhotoRequest\0322.mavsdk.rpc.ca" + "mera_server.RespondTakePhotoResponse\"\004\200\265" + "\030\001\022\201\001\n\023SubscribeStartVideo\0224.mavsdk.rpc." + "camera_server.SubscribeStartVideoRequest" + "\032,.mavsdk.rpc.camera_server.StartVideoRe" + "sponse\"\004\200\265\030\0000\001\022~\n\022SubscribeStopVideo\0223.m" + "avsdk.rpc.camera_server.SubscribeStopVid" + "eoRequest\032+.mavsdk.rpc.camera_server.Sto" + "pVideoResponse\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStar" + "tVideoStreaming\022=.mavsdk.rpc.camera_serv" + "er.SubscribeStartVideoStreamingRequest\0325" + ".mavsdk.rpc.camera_server.StartVideoStre" + "amingResponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopV" + "ideoStreaming\022<.mavsdk.rpc.camera_server" + ".SubscribeStopVideoStreamingRequest\0324.ma" + "vsdk.rpc.camera_server.StopVideoStreamin" + "gResponse\"\004\200\265\030\0000\001\022x\n\020SubscribeSetMode\0221." + "mavsdk.rpc.camera_server.SubscribeSetMod" + "eRequest\032).mavsdk.rpc.camera_server.SetM" + "odeResponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorage" + "Information\022<.mavsdk.rpc.camera_server.S" + "ubscribeStorageInformationRequest\0324.mavs" + "dk.rpc.camera_server.StorageInformationR" + "esponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInform" + "ation\022:.mavsdk.rpc.camera_server.Respond" + "StorageInformationRequest\032;.mavsdk.rpc.c" + "amera_server.RespondStorageInformationRe" + "sponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\022" + "7.mavsdk.rpc.camera_server.SubscribeCapt" + "ureStatusRequest\032/.mavsdk.rpc.camera_ser" + "ver.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Re" + "spondCaptureStatus\0225.mavsdk.rpc.camera_s" + "erver.RespondCaptureStatusRequest\0326.mavs" + "dk.rpc.camera_server.RespondCaptureStatu" + "sResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera_serv" + "erB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1189,7 +1189,7 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 5977, + 5989, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, @@ -7014,9 +7014,9 @@ inline void StorageInformation::SharedCtor(::_pb::Arena* arena) { , decltype(_impl_.storage_type_) { 0 } - , decltype(_impl_.read_speed_) { 0 } + , decltype(_impl_.read_speed_mib_s_) { 0 } - , decltype(_impl_.write_speed_) { 0 } + , decltype(_impl_.write_speed_mib_s_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; @@ -7046,8 +7046,8 @@ void StorageInformation::Clear() { (void) cached_has_bits; ::memset(&_impl_.used_storage_mib_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.write_speed_) - - reinterpret_cast(&_impl_.used_storage_mib_)) + sizeof(_impl_.write_speed_)); + reinterpret_cast(&_impl_.write_speed_mib_s_) - + reinterpret_cast(&_impl_.used_storage_mib_)) + sizeof(_impl_.write_speed_mib_s_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -7113,19 +7113,19 @@ const char* StorageInformation::_InternalParse(const char* ptr, ::_pbi::ParseCon goto handle_unusual; } continue; - // float read_speed = 7; + // float read_speed_mib_s = 7; case 7: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 61)) { - _impl_.read_speed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + _impl_.read_speed_mib_s_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; } continue; - // float write_speed = 8; + // float write_speed_mib_s = 8; case 8: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 69)) { - _impl_.write_speed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + _impl_.write_speed_mib_s_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else { goto handle_unusual; @@ -7214,26 +7214,26 @@ ::uint8_t* StorageInformation::_InternalSerialize( 6, this->_internal_storage_type(), target); } - // float read_speed = 7; + // float read_speed_mib_s = 7; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_read_speed = this->_internal_read_speed(); - ::uint32_t raw_read_speed; - memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); - if (raw_read_speed != 0) { + float tmp_read_speed_mib_s = this->_internal_read_speed_mib_s(); + ::uint32_t raw_read_speed_mib_s; + memcpy(&raw_read_speed_mib_s, &tmp_read_speed_mib_s, sizeof(tmp_read_speed_mib_s)); + if (raw_read_speed_mib_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 7, this->_internal_read_speed(), target); + 7, this->_internal_read_speed_mib_s(), target); } - // float write_speed = 8; + // float write_speed_mib_s = 8; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_write_speed = this->_internal_write_speed(); - ::uint32_t raw_write_speed; - memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); - if (raw_write_speed != 0) { + float tmp_write_speed_mib_s = this->_internal_write_speed_mib_s(); + ::uint32_t raw_write_speed_mib_s; + memcpy(&raw_write_speed_mib_s, &tmp_write_speed_mib_s, sizeof(tmp_write_speed_mib_s)); + if (raw_write_speed_mib_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 8, this->_internal_write_speed(), target); + 8, this->_internal_write_speed_mib_s(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -7297,21 +7297,21 @@ ::size_t StorageInformation::ByteSizeLong() const { ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_type()); } - // float read_speed = 7; + // float read_speed_mib_s = 7; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_read_speed = this->_internal_read_speed(); - ::uint32_t raw_read_speed; - memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); - if (raw_read_speed != 0) { + float tmp_read_speed_mib_s = this->_internal_read_speed_mib_s(); + ::uint32_t raw_read_speed_mib_s; + memcpy(&raw_read_speed_mib_s, &tmp_read_speed_mib_s, sizeof(tmp_read_speed_mib_s)); + if (raw_read_speed_mib_s != 0) { total_size += 5; } - // float write_speed = 8; + // float write_speed_mib_s = 8; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_write_speed = this->_internal_write_speed(); - ::uint32_t raw_write_speed; - memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); - if (raw_write_speed != 0) { + float tmp_write_speed_mib_s = this->_internal_write_speed_mib_s(); + ::uint32_t raw_write_speed_mib_s; + memcpy(&raw_write_speed_mib_s, &tmp_write_speed_mib_s, sizeof(tmp_write_speed_mib_s)); + if (raw_write_speed_mib_s != 0) { total_size += 5; } @@ -7364,18 +7364,18 @@ void StorageInformation::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, con _this->_internal_set_storage_type(from._internal_storage_type()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_read_speed = from._internal_read_speed(); - ::uint32_t raw_read_speed; - memcpy(&raw_read_speed, &tmp_read_speed, sizeof(tmp_read_speed)); - if (raw_read_speed != 0) { - _this->_internal_set_read_speed(from._internal_read_speed()); + float tmp_read_speed_mib_s = from._internal_read_speed_mib_s(); + ::uint32_t raw_read_speed_mib_s; + memcpy(&raw_read_speed_mib_s, &tmp_read_speed_mib_s, sizeof(tmp_read_speed_mib_s)); + if (raw_read_speed_mib_s != 0) { + _this->_internal_set_read_speed_mib_s(from._internal_read_speed_mib_s()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_write_speed = from._internal_write_speed(); - ::uint32_t raw_write_speed; - memcpy(&raw_write_speed, &tmp_write_speed, sizeof(tmp_write_speed)); - if (raw_write_speed != 0) { - _this->_internal_set_write_speed(from._internal_write_speed()); + float tmp_write_speed_mib_s = from._internal_write_speed_mib_s(); + ::uint32_t raw_write_speed_mib_s; + memcpy(&raw_write_speed_mib_s, &tmp_write_speed_mib_s, sizeof(tmp_write_speed_mib_s)); + if (raw_write_speed_mib_s != 0) { + _this->_internal_set_write_speed_mib_s(from._internal_write_speed_mib_s()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } @@ -7395,8 +7395,8 @@ void StorageInformation::InternalSwap(StorageInformation* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(StorageInformation, _impl_.write_speed_) - + sizeof(StorageInformation::_impl_.write_speed_) + PROTOBUF_FIELD_OFFSET(StorageInformation, _impl_.write_speed_mib_s_) + + sizeof(StorageInformation::_impl_.write_speed_mib_s_) - PROTOBUF_FIELD_OFFSET(StorageInformation, _impl_.used_storage_mib_)>( reinterpret_cast(&_impl_.used_storage_mib_), reinterpret_cast(&other->_impl_.used_storage_mib_)); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index c806ed898e..b8f07f46cf 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -5626,8 +5626,8 @@ class StorageInformation final : kStorageStatusFieldNumber = 4, kStorageIdFieldNumber = 5, kStorageTypeFieldNumber = 6, - kReadSpeedFieldNumber = 7, - kWriteSpeedFieldNumber = 8, + kReadSpeedMibSFieldNumber = 7, + kWriteSpeedMibSFieldNumber = 8, }; // float used_storage_mib = 1; void clear_used_storage_mib() ; @@ -5689,24 +5689,24 @@ class StorageInformation final : void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); public: - // float read_speed = 7; - void clear_read_speed() ; - float read_speed() const; - void set_read_speed(float value); + // float read_speed_mib_s = 7; + void clear_read_speed_mib_s() ; + float read_speed_mib_s() const; + void set_read_speed_mib_s(float value); private: - float _internal_read_speed() const; - void _internal_set_read_speed(float value); + float _internal_read_speed_mib_s() const; + void _internal_set_read_speed_mib_s(float value); public: - // float write_speed = 8; - void clear_write_speed() ; - float write_speed() const; - void set_write_speed(float value); + // float write_speed_mib_s = 8; + void clear_write_speed_mib_s() ; + float write_speed_mib_s() const; + void set_write_speed_mib_s(float value); private: - float _internal_write_speed() const; - void _internal_set_write_speed(float value); + float _internal_write_speed_mib_s() const; + void _internal_set_write_speed_mib_s(float value); public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) @@ -5723,8 +5723,8 @@ class StorageInformation final : int storage_status_; ::uint32_t storage_id_; int storage_type_; - float read_speed_; - float write_speed_; + float read_speed_mib_s_; + float write_speed_mib_s_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; @@ -8067,44 +8067,44 @@ inline void StorageInformation::_internal_set_storage_type(::mavsdk::rpc::camera _impl_.storage_type_ = value; } -// float read_speed = 7; -inline void StorageInformation::clear_read_speed() { - _impl_.read_speed_ = 0; +// float read_speed_mib_s = 7; +inline void StorageInformation::clear_read_speed_mib_s() { + _impl_.read_speed_mib_s_ = 0; } -inline float StorageInformation::read_speed() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.read_speed) - return _internal_read_speed(); +inline float StorageInformation::read_speed_mib_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.read_speed_mib_s) + return _internal_read_speed_mib_s(); } -inline void StorageInformation::set_read_speed(float value) { - _internal_set_read_speed(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.read_speed) +inline void StorageInformation::set_read_speed_mib_s(float value) { + _internal_set_read_speed_mib_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.read_speed_mib_s) } -inline float StorageInformation::_internal_read_speed() const { - return _impl_.read_speed_; +inline float StorageInformation::_internal_read_speed_mib_s() const { + return _impl_.read_speed_mib_s_; } -inline void StorageInformation::_internal_set_read_speed(float value) { +inline void StorageInformation::_internal_set_read_speed_mib_s(float value) { ; - _impl_.read_speed_ = value; + _impl_.read_speed_mib_s_ = value; } -// float write_speed = 8; -inline void StorageInformation::clear_write_speed() { - _impl_.write_speed_ = 0; +// float write_speed_mib_s = 8; +inline void StorageInformation::clear_write_speed_mib_s() { + _impl_.write_speed_mib_s_ = 0; } -inline float StorageInformation::write_speed() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.write_speed) - return _internal_write_speed(); +inline float StorageInformation::write_speed_mib_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StorageInformation.write_speed_mib_s) + return _internal_write_speed_mib_s(); } -inline void StorageInformation::set_write_speed(float value) { - _internal_set_write_speed(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.write_speed) +inline void StorageInformation::set_write_speed_mib_s(float value) { + _internal_set_write_speed_mib_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StorageInformation.write_speed_mib_s) } -inline float StorageInformation::_internal_write_speed() const { - return _impl_.write_speed_; +inline float StorageInformation::_internal_write_speed_mib_s() const { + return _impl_.write_speed_mib_s_; } -inline void StorageInformation::_internal_set_write_speed(float value) { +inline void StorageInformation::_internal_set_write_speed_mib_s(float value) { ; - _impl_.write_speed_ = value; + _impl_.write_speed_mib_s_ = value; } // ------------------------------------------------------------------- diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 40912b71ea..c0f7055ecf 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -437,9 +437,9 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_storage_type(translateToRpcStorageType(storage_information.storage_type)); - rpc_obj->set_read_speed(storage_information.read_speed); + rpc_obj->set_read_speed_mib_s(storage_information.read_speed_mib_s); - rpc_obj->set_write_speed(storage_information.write_speed); + rpc_obj->set_write_speed_mib_s(storage_information.write_speed_mib_s); return rpc_obj; } @@ -461,9 +461,9 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.storage_type = translateFromRpcStorageType(storage_information.storage_type()); - obj.read_speed = storage_information.read_speed(); + obj.read_speed_mib_s = storage_information.read_speed_mib_s(); - obj.write_speed = storage_information.write_speed(); + obj.write_speed_mib_s = storage_information.write_speed_mib_s(); return obj; } From ccd35203c92f7f1078e692a941a4bec161f171a0 Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 24 Jun 2023 09:59:36 +0800 Subject: [PATCH 07/25] camera : add format storage and reset settings function --- examples/camera_server/camera_client.cpp | 7 + examples/camera_server/camera_server.cpp | 7 + src/integration_tests/CMakeLists.txt | 1 + src/integration_tests/camera_format.cpp | 2 +- .../camera_reset_settings.cpp | 26 + src/mavsdk/plugins/camera/camera.cpp | 18 +- src/mavsdk/plugins/camera/camera_impl.cpp | 35 +- src/mavsdk/plugins/camera/camera_impl.h | 7 +- .../camera/include/plugins/camera/camera.h | 24 +- src/mavsdk/plugins/camera/mocks/camera_mock.h | 3 +- .../plugins/camera_server/camera_server.cpp | 22 + .../camera_server/camera_server_impl.cpp | 41 +- .../camera_server/camera_server_impl.h | 10 + .../plugins/camera_server/camera_server.h | 42 + .../src/generated/camera/camera.grpc.pb.cc | 42 + .../src/generated/camera/camera.grpc.pb.h | 177 ++- .../src/generated/camera/camera.pb.cc | 788 ++++++++++--- .../src/generated/camera/camera.pb.h | 480 +++++++- .../camera_server/camera_server.grpc.pb.cc | 70 ++ .../camera_server/camera_server.grpc.pb.h | 326 +++++- .../camera_server/camera_server.pb.cc | 819 ++++++++++--- .../camera_server/camera_server.pb.h | 1014 ++++++++++++++--- .../src/plugins/camera/camera_service_impl.h | 32 +- .../camera_server_service_impl.h | 82 ++ 24 files changed, 3532 insertions(+), 543 deletions(-) create mode 100644 src/integration_tests/camera_reset_settings.cpp diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 5fc54bd624..243f9d20dd 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -88,4 +88,11 @@ void do_camera_operation(mavsdk::Camera& camera) operation_result = camera.stop_video_streaming(2); std::cout << "stop video streaming result : " << operation_result << std::endl; + + // format the storage with special storage id test + operation_result = camera.format_storage(11); + std::cout << "format storage result : " << operation_result << std::endl; + + operation_result = camera.reset_settings(); + std::cout << "Reset camera settings result : " << operation_result << std::endl; } diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 8e89554bb3..03861656cd 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -156,4 +156,11 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) } camera_server.respond_capture_status(capture_status); }); + + camera_server.subscribe_format_storage([](int storage_id) { + std::cout << "format storage with id : " << storage_id << std::endl; + }); + + camera_server.subscribe_reset_settings( + [](int camera_id) { std::cout << "reset camera settings" << std::endl; }); } \ No newline at end of file diff --git a/src/integration_tests/CMakeLists.txt b/src/integration_tests/CMakeLists.txt index 94c83caebe..70ed009503 100644 --- a/src/integration_tests/CMakeLists.txt +++ b/src/integration_tests/CMakeLists.txt @@ -18,6 +18,7 @@ add_executable(integration_tests_runner camera_take_photo.cpp camera_take_photo_interval.cpp camera_format.cpp + camera_reset_settings.cpp camera_test_helpers.cpp connection.cpp follow_me.cpp diff --git a/src/integration_tests/camera_format.cpp b/src/integration_tests/camera_format.cpp index 869892dc2a..5c9b1715ce 100644 --- a/src/integration_tests/camera_format.cpp +++ b/src/integration_tests/camera_format.cpp @@ -22,5 +22,5 @@ TEST(CameraTest, Format) auto camera = std::make_shared(system); - EXPECT_EQ(Camera::Result::Success, camera->format_storage()); + EXPECT_EQ(Camera::Result::Success, camera->format_storage(1)); } diff --git a/src/integration_tests/camera_reset_settings.cpp b/src/integration_tests/camera_reset_settings.cpp new file mode 100644 index 0000000000..bbf0fc4b67 --- /dev/null +++ b/src/integration_tests/camera_reset_settings.cpp @@ -0,0 +1,26 @@ +#include "integration_test_helper.h" +#include "mavsdk.h" +#include +#include +#include +#include "plugins/camera/camera.h" + +using namespace mavsdk; + +TEST(CameraTest, ResetSettings) +{ + Mavsdk mavsdk; + + ConnectionResult ret = mavsdk.add_udp_connection(); + ASSERT_EQ(ret, ConnectionResult::Success); + + // Wait for system to connect via heartbeat. + std::this_thread::sleep_for(std::chrono::seconds(2)); + + auto system = mavsdk.systems().at(0); + ASSERT_TRUE(system->has_camera()); + + auto camera = std::make_shared(system); + + EXPECT_EQ(Camera::Result::Success, camera->reset_settings()); +} diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index 21abdc9cec..e7e9126d57 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -239,14 +239,14 @@ std::pair Camera::get_setting(Setting setting) return _impl->get_setting(setting); } -void Camera::format_storage_async(const ResultCallback callback) +void Camera::format_storage_async(int32_t storage_id, const ResultCallback callback) { - _impl->format_storage_async(callback); + _impl->format_storage_async(storage_id, callback); } -Camera::Result Camera::format_storage() const +Camera::Result Camera::format_storage(int32_t storage_id) const { - return _impl->format_storage(); + return _impl->format_storage(storage_id); } Camera::Result Camera::select_camera(int32_t camera_id) const @@ -254,6 +254,16 @@ Camera::Result Camera::select_camera(int32_t camera_id) const return _impl->select_camera(camera_id); } +void Camera::reset_settings_async(const ResultCallback callback) +{ + _impl->reset_settings_async(callback); +} + +Camera::Result Camera::reset_settings() const +{ + return _impl->reset_settings(); +} + std::ostream& operator<<(std::ostream& str, Camera::Result const& result) { switch (result) { diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index f86d836465..df8dc0795e 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -1929,22 +1929,22 @@ void CameraImpl::request_camera_information() _system_impl->send_command_async(command_camera_info, nullptr); } -Camera::Result CameraImpl::format_storage() +Camera::Result CameraImpl::format_storage(int32_t storage_id) { auto prom = std::make_shared>(); auto ret = prom->get_future(); - format_storage_async([prom](Camera::Result result) { prom->set_value(result); }); + format_storage_async(storage_id, [prom](Camera::Result result) { prom->set_value(result); }); return ret.get(); } -void CameraImpl::format_storage_async(Camera::ResultCallback callback) +void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback callback) { MavlinkCommandSender::CommandLong cmd_format{}; cmd_format.command = MAV_CMD_STORAGE_FORMAT; - cmd_format.params.maybe_param1 = 1.0f; // storage ID + cmd_format.params.maybe_param1 = storage_id; // storage ID cmd_format.params.maybe_param2 = 1.0f; // format cmd_format.params.maybe_param3 = 1.0f; // clear cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; @@ -1963,6 +1963,33 @@ void CameraImpl::format_storage_async(Camera::ResultCallback callback) }); } +Camera::Result CameraImpl::reset_settings() +{ + auto prom = std::make_shared>(); + auto ret = prom->get_future(); + + reset_settings_async([prom](Camera::Result result) { prom->set_value(result); }); + + return ret.get(); +} +void CameraImpl::reset_settings_async(const Camera::ResultCallback callback) +{ + MavlinkCommandSender::CommandLong cmd_format{}; + + cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS; + cmd_format.params.maybe_param1 = 1.0; // reset + cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + + _system_impl->send_command_async( + cmd_format, [this, callback](MavlinkCommandSender::Result result, float progress) { + UNUSED(progress); + + receive_command_result(result, [this, callback](Camera::Result camera_result) { + callback(camera_result); + }); + }); +} + void CameraImpl::reset_following_format_storage() { { diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index f9f3f7d4f1..8ff928d65f 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -86,8 +86,11 @@ class CameraImpl : public PluginImplBase { subscribe_possible_setting_options(const Camera::PossibleSettingOptionsCallback& callback); void unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle); - Camera::Result format_storage(); - void format_storage_async(Camera::ResultCallback callback); + Camera::Result format_storage(int32_t storage_id); + void format_storage_async(int32_t storage_id, const Camera::ResultCallback callback); + + Camera::Result reset_settings(); + void reset_settings_async(const Camera::ResultCallback callback); std::pair> list_photos(Camera::PhotosRange photos_range); diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index d9f4c93a6c..57bdaa5937 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -875,7 +875,7 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'format_storage' for the blocking counterpart. */ - void format_storage_async(const ResultCallback callback); + void format_storage_async(int32_t storage_id, const ResultCallback callback); /** * @brief Format storage (e.g. SD card) in camera. @@ -886,7 +886,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result format_storage() const; + Result format_storage(int32_t storage_id) const; /** * @brief Select current camera . @@ -899,6 +899,26 @@ class Camera : public PluginBase { */ Result select_camera(int32_t camera_id) const; + /** + * @brief Reset all settings in camera. + * + * This will reset all camera settings to default value + * + * This function is non-blocking. See 'reset_settings' for the blocking counterpart. + */ + void reset_settings_async(const ResultCallback callback); + + /** + * @brief Reset all settings in camera. + * + * This will reset all camera settings to default value + * + * This function is blocking. See 'reset_settings_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result reset_settings() const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/camera/mocks/camera_mock.h b/src/mavsdk/plugins/camera/mocks/camera_mock.h index 9941057012..fbfbc920c1 100644 --- a/src/mavsdk/plugins/camera/mocks/camera_mock.h +++ b/src/mavsdk/plugins/camera/mocks/camera_mock.h @@ -44,11 +44,12 @@ class MockCamera { unsubscribe_possible_setting_options, void(Camera::PossibleSettingOptionsHandle)){}; MOCK_CONST_METHOD3( set_option_async, void(Camera::ResultCallback, const std::string&, const Camera::Option)){}; - MOCK_CONST_METHOD0(format_storage, Camera::Result()){}; + MOCK_CONST_METHOD1(format_storage, Camera::Result(int32_t)){}; MOCK_CONST_METHOD1( list_photos, std::pair>(Camera::PhotosRange)){}; MOCK_CONST_METHOD1(select_camera, Camera::Result(int32_t)){}; + MOCK_CONST_METHOD0(reset_settings, Camera::Result()){}; }; } // namespace testing diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 8f26c2f099..e49200bf11 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -137,6 +137,28 @@ CameraServer::Result CameraServer::respond_capture_status(CaptureStatus capture_ return _impl->respond_capture_status(capture_status); } +CameraServer::FormatStorageHandle +CameraServer::subscribe_format_storage(const FormatStorageCallback& callback) +{ + return _impl->subscribe_format_storage(callback); +} + +void CameraServer::unsubscribe_format_storage(FormatStorageHandle handle) +{ + _impl->unsubscribe_format_storage(handle); +} + +CameraServer::ResetSettingsHandle +CameraServer::subscribe_reset_settings(const ResetSettingsCallback& callback) +{ + return _impl->subscribe_reset_settings(callback); +} + +void CameraServer::unsubscribe_reset_settings(ResetSettingsHandle handle) +{ + _impl->unsubscribe_reset_settings(handle); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index cde1a81e8d..bfe49c9fe3 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -500,6 +500,27 @@ CameraServerImpl::respond_capture_status(CameraServer::CaptureStatus capture_sta return CameraServer::Result::Success; } +CameraServer::FormatStorageHandle +CameraServerImpl::subscribe_format_storage(const CameraServer::FormatStorageCallback& callback) +{ + return _format_storage_callbacks.subscribe(callback); +} +void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHandle handle) +{ + _format_storage_callbacks.unsubscribe(handle); +} + +CameraServer::ResetSettingsHandle +CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback) +{ + return _reset_settings_callbacks.subscribe(callback); +} + +void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle) +{ + _reset_settings_callbacks.unsubscribe(handle); +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -733,14 +754,18 @@ CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLo auto format = static_cast(command.params.param2); auto reset_image_log = static_cast(command.params.param3); - UNUSED(storage_id); UNUSED(format); UNUSED(reset_image_log); + if (_format_storage_callbacks.empty()) { + LogDebug() << "process storage format requested with no storage format subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - LogDebug() << "unsupported storage format request"; + _format_storage_callbacks(storage_id); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional CameraServerImpl::process_camera_capture_status_request( @@ -810,10 +835,16 @@ CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::Co UNUSED(reset); - LogDebug() << "unsupported reset camera settings request"; + if (_reset_settings_callbacks.empty()) { + LogDebug() << "reset camera settings requested with no camera settings subscriber"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } + + _reset_settings_callbacks(0); return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + command, MAV_RESULT::MAV_RESULT_ACCEPTED); } std::optional diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 34dcb11d20..78e462ec55 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -54,6 +54,14 @@ class CameraServerImpl : public ServerPluginImplBase { void unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle); CameraServer::Result respond_capture_status(CameraServer::CaptureStatus capture_status) const; + CameraServer::FormatStorageHandle + subscribe_format_storage(const CameraServer::FormatStorageCallback& callback); + void unsubscribe_format_storage(CameraServer::FormatStorageHandle handle); + + CameraServer::ResetSettingsHandle + subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback); + void unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle); + private: enum StatusFlags { IN_PROGRESS = 1 << 0, @@ -85,6 +93,8 @@ class CameraServerImpl : public ServerPluginImplBase { CallbackList _set_mode_callbacks{}; CallbackList _storage_information_callbacks{}; CallbackList _capture_status_callbacks{}; + CallbackList _format_storage_callbacks{}; + CallbackList _reset_settings_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; uint8_t _last_storage_id; diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 57fe06d30e..a9caf7bf71 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -579,6 +579,48 @@ class CameraServer : public ServerPluginBase { */ Result respond_capture_status(CaptureStatus capture_status) const; + /** + * @brief Callback type for subscribe_format_storage. + */ + using FormatStorageCallback = std::function; + + /** + * @brief Handle type for subscribe_format_storage. + */ + using FormatStorageHandle = Handle; + + /** + * @brief Subscribe to format storage requests. Each request received should response to using + * FormatStorageResponse + */ + FormatStorageHandle subscribe_format_storage(const FormatStorageCallback& callback); + + /** + * @brief Unsubscribe from subscribe_format_storage + */ + void unsubscribe_format_storage(FormatStorageHandle handle); + + /** + * @brief Callback type for subscribe_reset_settings. + */ + using ResetSettingsCallback = std::function; + + /** + * @brief Handle type for subscribe_reset_settings. + */ + using ResetSettingsHandle = Handle; + + /** + * @brief Subscribe to reset settings requests. Each request received should response to using + * ResetSettingsResponse + */ + ResetSettingsHandle subscribe_reset_settings(const ResetSettingsCallback& callback); + + /** + * @brief Unsubscribe from subscribe_reset_settings + */ + void unsubscribe_reset_settings(ResetSettingsHandle handle); + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc index 3808ce2d5a..ebbb967ff2 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc @@ -45,6 +45,7 @@ static const char* CameraService_method_names[] = { "/mavsdk.rpc.camera.CameraService/GetSetting", "/mavsdk.rpc.camera.CameraService/FormatStorage", "/mavsdk.rpc.camera.CameraService/SelectCamera", + "/mavsdk.rpc.camera.CameraService/ResetSettings", }; std::unique_ptr< CameraService::Stub> CameraService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -75,6 +76,7 @@ CameraService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& chan , rpcmethod_GetSetting_(CameraService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_FormatStorage_(CameraService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SelectCamera_(CameraService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ResetSettings_(CameraService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status CameraService::Stub::Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::mavsdk::rpc::camera::PrepareResponse* response) { @@ -511,6 +513,29 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>* return result; } +::grpc::Status CameraService::Stub::ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::mavsdk::rpc::camera::ResetSettingsResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ResetSettings_, context, request, response); +} + +void CameraService::Stub::async::ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ResetSettings_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ResetSettings_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>* CameraService::Stub::PrepareAsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::ResetSettingsResponse, ::mavsdk::rpc::camera::ResetSettingsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ResetSettings_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>* CameraService::Stub::AsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncResetSettingsRaw(context, request, cq); + result->StartCall(); + return result; +} + CameraService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[0], @@ -722,6 +747,16 @@ CameraService::Service::Service() { ::mavsdk::rpc::camera::SelectCameraResponse* resp) { return service->SelectCamera(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[21], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::ResetSettingsRequest* req, + ::mavsdk::rpc::camera::ResetSettingsResponse* resp) { + return service->ResetSettings(ctx, req, resp); + }, this))); } CameraService::Service::~Service() { @@ -874,6 +909,13 @@ ::grpc::Status CameraService::Service::SelectCamera(::grpc::ServerContext* conte return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::ResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* 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/camera/camera.grpc.pb.h b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h index a9e3e76791..5c8955af32 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h @@ -256,6 +256,17 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>> PrepareAsyncSelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>>(PrepareAsyncSelectCameraRaw(context, request, cq)); } + // + // Reset all settings in camera. + // + // This will reset all camera settings to default value + virtual ::grpc::Status ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::mavsdk::rpc::camera::ResetSettingsResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>> AsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>>(AsyncResetSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>> PrepareAsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>>(PrepareAsyncResetSettingsRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -344,6 +355,12 @@ class CameraService final { // Bind the plugin instance to a specific camera_id virtual void SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, std::function) = 0; virtual void SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Reset all settings in camera. + // + // This will reset all camera settings to default value + virtual void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, std::function) = 0; + virtual void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -398,6 +415,8 @@ class CameraService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FormatStorageResponse>* PrepareAsyncFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>* AsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>* PrepareAsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>* AsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>* PrepareAsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -563,6 +582,13 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>> PrepareAsyncSelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>>(PrepareAsyncSelectCameraRaw(context, request, cq)); } + ::grpc::Status ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::mavsdk::rpc::camera::ResetSettingsResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>> AsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>>(AsyncResetSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>> PrepareAsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>>(PrepareAsyncResetSettingsRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -601,6 +627,8 @@ class CameraService final { void FormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, std::function) override; void SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, std::function) override; + void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -661,6 +689,8 @@ class CameraService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FormatStorageResponse>* PrepareAsyncFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>* AsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>* PrepareAsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>* AsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>* PrepareAsyncResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_Prepare_; const ::grpc::internal::RpcMethod rpcmethod_TakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_StartPhotoInterval_; @@ -682,6 +712,7 @@ class CameraService final { const ::grpc::internal::RpcMethod rpcmethod_GetSetting_; const ::grpc::internal::RpcMethod rpcmethod_FormatStorage_; const ::grpc::internal::RpcMethod rpcmethod_SelectCamera_; + const ::grpc::internal::RpcMethod rpcmethod_ResetSettings_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -760,6 +791,11 @@ class CameraService final { // // Bind the plugin instance to a specific camera_id virtual ::grpc::Status SelectCamera(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response); + // + // Reset all settings in camera. + // + // This will reset all camera settings to default value + virtual ::grpc::Status ResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response); }; template class WithAsyncMethod_Prepare : public BaseClass { @@ -1181,7 +1217,27 @@ class CameraService final { ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_Prepare > > > > > > > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ResetSettings() { + ::grpc::Service::MarkMethodAsync(21); + } + ~WithAsyncMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ResetSettingsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_Prepare > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_Prepare : public BaseClass { private: @@ -1714,7 +1770,34 @@ class CameraService final { virtual ::grpc::ServerUnaryReactor* SelectCamera( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_Prepare > > > > > > > > > > > > > > > > > > > > CallbackService; + template + class WithCallbackMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_ResetSettings() { + ::grpc::Service::MarkMethodCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response) { return this->ResetSettings(context, request, response); }));} + void SetMessageAllocatorFor_ResetSettings( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(21); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_Prepare > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_Prepare : public BaseClass { @@ -2074,6 +2157,23 @@ class CameraService final { } }; template + class WithGenericMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_ResetSettings() { + ::grpc::Service::MarkMethodGeneric(21); + } + ~WithGenericMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_Prepare : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2494,6 +2594,26 @@ class CameraService final { } }; template + class WithRawMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ResetSettings() { + ::grpc::Service::MarkMethodRaw(21); + } + ~WithRawMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestResetSettings(::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(21, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_Prepare : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2956,6 +3076,28 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ResetSettings() { + ::grpc::Service::MarkMethodRawCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ResetSettings(context, request, response); })); + } + ~WithRawCallbackMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_Prepare : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -3333,7 +3475,34 @@ class CameraService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedSelectCamera(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::SelectCameraRequest,::mavsdk::rpc::camera::SelectCameraResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ResetSettings() { + ::grpc::Service::MarkMethodStreamed(21, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>* streamer) { + return this->StreamedResetSettings(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedResetSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ResetSettingsRequest,::mavsdk::rpc::camera::ResetSettingsResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeMode : public BaseClass { private: @@ -3524,7 +3693,7 @@ class CameraService final { virtual ::grpc::Status StreamedSubscribePossibleSettingOptions(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest,::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeMode > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace camera diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 81e95c2d2e..81acedcb8c 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -595,7 +595,10 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetSettingResponseDefaultTypeInternal _GetSettingResponse_default_instance_; template PROTOBUF_CONSTEXPR FormatStorageRequest::FormatStorageRequest( - ::_pbi::ConstantInitialized) {} + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.storage_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} struct FormatStorageRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR FormatStorageRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~FormatStorageRequestDefaultTypeInternal() {} @@ -655,6 +658,35 @@ struct SelectCameraRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SelectCameraRequestDefaultTypeInternal _SelectCameraRequest_default_instance_; template +PROTOBUF_CONSTEXPR ResetSettingsRequest::ResetSettingsRequest( + ::_pbi::ConstantInitialized) {} +struct ResetSettingsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ResetSettingsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ResetSettingsRequestDefaultTypeInternal() {} + union { + ResetSettingsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetSettingsRequestDefaultTypeInternal _ResetSettingsRequest_default_instance_; +template +PROTOBUF_CONSTEXPR ResetSettingsResponse::ResetSettingsResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_result_)*/nullptr} {} +struct ResetSettingsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ResetSettingsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ResetSettingsResponseDefaultTypeInternal() {} + union { + ResetSettingsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; +template PROTOBUF_CONSTEXPR CameraResult::CameraResult( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.result_str_)*/ { @@ -960,7 +992,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[54]; +static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[56]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_2fcamera_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_2fcamera_2eproto = nullptr; @@ -1326,6 +1358,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageRequest, _impl_.storage_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1356,6 +1389,24 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SelectCameraRequest, _impl_.camera_id_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsRequest, _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::camera::ResetSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsResponse, _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::camera::ResetSettingsResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraResult, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1565,21 +1616,23 @@ static const ::_pbi::MigrationSchema { 330, 339, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, { 340, 350, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, { 352, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, - { 360, 369, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, - { 370, 379, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, - { 380, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, - { 389, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, - { 399, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, - { 411, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, - { 423, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, - { 434, 449, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, - { 456, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, - { 471, 482, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, - { 485, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, - { 503, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, - { 513, 525, -1, sizeof(::mavsdk::rpc::camera::Setting)}, - { 529, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, - { 541, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + { 361, 370, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, + { 371, 380, -1, sizeof(::mavsdk::rpc::camera::SelectCameraResponse)}, + { 381, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, + { 390, -1, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsRequest)}, + { 398, 407, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsResponse)}, + { 408, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, + { 418, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, + { 430, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, + { 442, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, + { 453, 468, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, + { 475, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, + { 490, 501, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, + { 504, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, + { 522, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, + { 532, 544, -1, sizeof(::mavsdk::rpc::camera::Setting)}, + { 548, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, + { 560, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1625,6 +1678,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera::_FormatStorageResponse_default_instance_._instance, &::mavsdk::rpc::camera::_SelectCameraResponse_default_instance_._instance, &::mavsdk::rpc::camera::_SelectCameraRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_ResetSettingsRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_ResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera::_CameraResult_default_instance_._instance, &::mavsdk::rpc::camera::_Position_default_instance_._instance, &::mavsdk::rpc::camera::_Quaternion_default_instance_._instance, @@ -1699,139 +1754,145 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "ng\"y\n\022GetSettingResponse\0226\n\rcamera_resul" "t\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult" "\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera.Se" - "tting\"\026\n\024FormatStorageRequest\"O\n\025FormatS" - "torageResponse\0226\n\rcamera_result\030\001 \001(\0132\037." - "mavsdk.rpc.camera.CameraResult\"N\n\024Select" - "CameraResponse\0226\n\rcamera_result\030\001 \001(\0132\037." - "mavsdk.rpc.camera.CameraResult\"(\n\023Select" - "CameraRequest\022\021\n\tcamera_id\030\001 \001(\005\"\301\002\n\014Cam" - "eraResult\0226\n\006result\030\001 \001(\0162&.mavsdk.rpc.c" - "amera.CameraResult.Result\022\022\n\nresult_str\030" - "\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" - "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" - "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" - "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" - "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" - "M\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020\t\"q\n\010" - "Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongit" - "ude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001" - "(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\nQuate" - "rnion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t" - "\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg\030\001 \001(" - "\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001(\002\"\377\001" - "\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.mavsdk" - ".rpc.camera.Position\022:\n\023attitude_quatern" - "ion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quaternion" - "\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.mavsdk." - "rpc.camera.EulerAngle\022\023\n\013time_utc_us\030\004 \001" - "(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001(\005\022\020\n" - "\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSettings\022" - "\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizontal_res" - "olution_pix\030\002 \001(\r\022\037\n\027vertical_resolution" - "_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n\014rota" - "tion_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022horizonta" - "l_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo\0228\n\010s" - "ettings\030\001 \001(\0132&.mavsdk.rpc.camera.VideoS" - "treamSettings\022D\n\006status\030\002 \001(\01624.mavsdk.r" - "pc.camera.VideoStreamInfo.VideoStreamSta" - "tus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc.camer" - "a.VideoStreamInfo.VideoStreamSpectrum\"]\n" - "\021VideoStreamStatus\022#\n\037VIDEO_STREAM_STATU" - "S_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STATUS_I" - "N_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!\n\035" - "VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VIDEO" - "_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VIDE" - "O_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006Status\022" - "\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval_on\030\002" - " \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025availa" - "ble_storage_mib\030\004 \001(\002\022\031\n\021total_storage_m" - "ib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022\031\n\021me" - "dia_folder_name\030\007 \001(\t\022\?\n\016storage_status\030" - "\010 \001(\0162\'.mavsdk.rpc.camera.Status.Storage" - "Status\022\022\n\nstorage_id\030\t \001(\r\022;\n\014storage_ty" - "pe\030\n \001(\0162%.mavsdk.rpc.camera.Status.Stor" - "ageType\"\221\001\n\rStorageStatus\022 \n\034STORAGE_STA" - "TUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_UN" - "FORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTED\020" - "\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001\n\013" - "StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022\032\n" - "\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_TYP" - "E_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017STOR" - "AGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001\"7" - "\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022option_de" - "scription\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetting_id" - "\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t\022)\n\006o" - "ption\030\003 \001(\0132\031.mavsdk.rpc.camera.Option\022\020" - "\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022\022\n\nse" - "tting_id\030\001 \001(\t\022\033\n\023setting_description\030\002 " - "\001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.camera" - ".Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Informatio" - "n\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001" - "(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizonta" - "l_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_senso" - "r_size_mm\030\005 \001(\002\022 \n\030horizontal_resolution" - "_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 \001(" - "\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHOT" - "O\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022\024\n\020PH" - "OTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SINCE_C" - "ONNECTION\020\0012\323\021\n\rCameraService\022R\n\007Prepare" - "\022!.mavsdk.rpc.camera.PrepareRequest\032\".ma" - "vsdk.rpc.camera.PrepareResponse\"\000\022X\n\tTak" - "ePhoto\022#.mavsdk.rpc.camera.TakePhotoRequ" - "est\032$.mavsdk.rpc.camera.TakePhotoRespons" - "e\"\000\022s\n\022StartPhotoInterval\022,.mavsdk.rpc.c" - "amera.StartPhotoIntervalRequest\032-.mavsdk" - ".rpc.camera.StartPhotoIntervalResponse\"\000" - "\022p\n\021StopPhotoInterval\022+.mavsdk.rpc.camer" - "a.StopPhotoIntervalRequest\032,.mavsdk.rpc." - "camera.StopPhotoIntervalResponse\"\000\022[\n\nSt" - "artVideo\022$.mavsdk.rpc.camera.StartVideoR" - "equest\032%.mavsdk.rpc.camera.StartVideoRes" - "ponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.camera" - ".StopVideoRequest\032$.mavsdk.rpc.camera.St" - "opVideoResponse\"\000\022z\n\023StartVideoStreaming" - "\022-.mavsdk.rpc.camera.StartVideoStreaming" - "Request\032..mavsdk.rpc.camera.StartVideoSt" - "reamingResponse\"\004\200\265\030\001\022w\n\022StopVideoStream" - "ing\022,.mavsdk.rpc.camera.StopVideoStreami" - "ngRequest\032-.mavsdk.rpc.camera.StopVideoS" - "treamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!.mavs" - "dk.rpc.camera.SetModeRequest\032\".mavsdk.rp" - "c.camera.SetModeResponse\"\000\022[\n\nListPhotos" - "\022$.mavsdk.rpc.camera.ListPhotosRequest\032%" - ".mavsdk.rpc.camera.ListPhotosResponse\"\000\022" - "]\n\rSubscribeMode\022\'.mavsdk.rpc.camera.Sub" - "scribeModeRequest\032\037.mavsdk.rpc.camera.Mo" - "deResponse\"\0000\001\022r\n\024SubscribeInformation\022." - ".mavsdk.rpc.camera.SubscribeInformationR" - "equest\032&.mavsdk.rpc.camera.InformationRe" - "sponse\"\0000\001\022~\n\030SubscribeVideoStreamInfo\0222" - ".mavsdk.rpc.camera.SubscribeVideoStreamI" - "nfoRequest\032*.mavsdk.rpc.camera.VideoStre" - "amInfoResponse\"\0000\001\022v\n\024SubscribeCaptureIn" - "fo\022..mavsdk.rpc.camera.SubscribeCaptureI" - "nfoRequest\032&.mavsdk.rpc.camera.CaptureIn" - "foResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStatus\022)." - "mavsdk.rpc.camera.SubscribeStatusRequest" - "\032!.mavsdk.rpc.camera.StatusResponse\"\0000\001\022" - "\202\001\n\030SubscribeCurrentSettings\0222.mavsdk.rp" - "c.camera.SubscribeCurrentSettingsRequest" - "\032*.mavsdk.rpc.camera.CurrentSettingsResp" - "onse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleSettin" - "gOptions\0229.mavsdk.rpc.camera.SubscribePo" - "ssibleSettingOptionsRequest\0321.mavsdk.rpc" - ".camera.PossibleSettingOptionsResponse\"\000" - "0\001\022[\n\nSetSetting\022$.mavsdk.rpc.camera.Set" - "SettingRequest\032%.mavsdk.rpc.camera.SetSe" - "ttingResponse\"\000\022[\n\nGetSetting\022$.mavsdk.r" - "pc.camera.GetSettingRequest\032%.mavsdk.rpc" - ".camera.GetSettingResponse\"\000\022d\n\rFormatSt" - "orage\022\'.mavsdk.rpc.camera.FormatStorageR" - "equest\032(.mavsdk.rpc.camera.FormatStorage" - "Response\"\000\022e\n\014SelectCamera\022&.mavsdk.rpc." - "camera.SelectCameraRequest\032\'.mavsdk.rpc." - "camera.SelectCameraResponse\"\004\200\265\030\001B\037\n\020io." - "mavsdk.cameraB\013CameraProtob\006proto3" + "tting\"*\n\024FormatStorageRequest\022\022\n\nstorage" + "_id\030\001 \001(\005\"O\n\025FormatStorageResponse\0226\n\rca" + "mera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Ca" + "meraResult\"N\n\024SelectCameraResponse\0226\n\rca" + "mera_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Ca" + "meraResult\"(\n\023SelectCameraRequest\022\021\n\tcam" + "era_id\030\001 \001(\005\"\026\n\024ResetSettingsRequest\"O\n\025" + "ResetSettingsResponse\0226\n\rcamera_result\030\001" + " \001(\0132\037.mavsdk.rpc.camera.CameraResult\"\301\002" + "\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.mavsdk." + "rpc.camera.CameraResult.Result\022\022\n\nresult" + "_str\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020" + "\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGR" + "ESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020" + "\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022" + "\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_" + "SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020" + "\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rl" + "ongitude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_" + "m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\n" + "Quaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 " + "\001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg" + "\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001" + "(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.m" + "avsdk.rpc.camera.Position\022:\n\023attitude_qu" + "aternion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quate" + "rnion\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.ma" + "vsdk.rpc.camera.EulerAngle\022\023\n\013time_utc_u" + "s\030\004 \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001" + "(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSett" + "ings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizonta" + "l_resolution_pix\030\002 \001(\r\022\037\n\027vertical_resol" + "ution_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n" + "\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022hori" + "zontal_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo" + "\0228\n\010settings\030\001 \001(\0132&.mavsdk.rpc.camera.V" + "ideoStreamSettings\022D\n\006status\030\002 \001(\01624.mav" + "sdk.rpc.camera.VideoStreamInfo.VideoStre" + "amStatus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc." + "camera.VideoStreamInfo.VideoStreamSpectr" + "um\"]\n\021VideoStreamStatus\022#\n\037VIDEO_STREAM_" + "STATUS_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STA" + "TUS_IN_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectru" + "m\022!\n\035VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#" + "VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n" + "\036VIDEO_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006St" + "atus\022\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval" + "_on\030\002 \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025a" + "vailable_storage_mib\030\004 \001(\002\022\031\n\021total_stor" + "age_mib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022" + "\031\n\021media_folder_name\030\007 \001(\t\022\?\n\016storage_st" + "atus\030\010 \001(\0162\'.mavsdk.rpc.camera.Status.St" + "orageStatus\022\022\n\nstorage_id\030\t \001(\r\022;\n\014stora" + "ge_type\030\n \001(\0162%.mavsdk.rpc.camera.Status" + ".StorageType\"\221\001\n\rStorageStatus\022 \n\034STORAG" + "E_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STAT" + "US_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMA" + "TTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003" + "\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN" + "\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAG" + "E_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n" + "\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER" + "\020\376\001\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022opti" + "on_description\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetti" + "ng_id\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t" + "\022)\n\006option\030\003 \001(\0132\031.mavsdk.rpc.camera.Opt" + "ion\022\020\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022" + "\022\n\nsetting_id\030\001 \001(\t\022\033\n\023setting_descripti" + "on\030\002 \001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.c" + "amera.Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Infor" + "mation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_nam" + "e\030\002 \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031hori" + "zontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_" + "sensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resol" + "ution_px\030\006 \001(\r\022\036\n\026vertical_resolution_px" + "\030\007 \001(\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE" + "_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022" + "\024\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SI" + "NCE_CONNECTION\020\0012\271\022\n\rCameraService\022R\n\007Pr" + "epare\022!.mavsdk.rpc.camera.PrepareRequest" + "\032\".mavsdk.rpc.camera.PrepareResponse\"\000\022X" + "\n\tTakePhoto\022#.mavsdk.rpc.camera.TakePhot" + "oRequest\032$.mavsdk.rpc.camera.TakePhotoRe" + "sponse\"\000\022s\n\022StartPhotoInterval\022,.mavsdk." + "rpc.camera.StartPhotoIntervalRequest\032-.m" + "avsdk.rpc.camera.StartPhotoIntervalRespo" + "nse\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.rpc." + "camera.StopPhotoIntervalRequest\032,.mavsdk" + ".rpc.camera.StopPhotoIntervalResponse\"\000\022" + "[\n\nStartVideo\022$.mavsdk.rpc.camera.StartV" + "ideoRequest\032%.mavsdk.rpc.camera.StartVid" + "eoResponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.c" + "amera.StopVideoRequest\032$.mavsdk.rpc.came" + "ra.StopVideoResponse\"\000\022z\n\023StartVideoStre" + "aming\022-.mavsdk.rpc.camera.StartVideoStre" + "amingRequest\032..mavsdk.rpc.camera.StartVi" + "deoStreamingResponse\"\004\200\265\030\001\022w\n\022StopVideoS" + "treaming\022,.mavsdk.rpc.camera.StopVideoSt" + "reamingRequest\032-.mavsdk.rpc.camera.StopV" + "ideoStreamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!" + ".mavsdk.rpc.camera.SetModeRequest\032\".mavs" + "dk.rpc.camera.SetModeResponse\"\000\022[\n\nListP" + "hotos\022$.mavsdk.rpc.camera.ListPhotosRequ" + "est\032%.mavsdk.rpc.camera.ListPhotosRespon" + "se\"\000\022]\n\rSubscribeMode\022\'.mavsdk.rpc.camer" + "a.SubscribeModeRequest\032\037.mavsdk.rpc.came" + "ra.ModeResponse\"\0000\001\022r\n\024SubscribeInformat" + "ion\022..mavsdk.rpc.camera.SubscribeInforma" + "tionRequest\032&.mavsdk.rpc.camera.Informat" + "ionResponse\"\0000\001\022~\n\030SubscribeVideoStreamI" + "nfo\0222.mavsdk.rpc.camera.SubscribeVideoSt" + "reamInfoRequest\032*.mavsdk.rpc.camera.Vide" + "oStreamInfoResponse\"\0000\001\022v\n\024SubscribeCapt" + "ureInfo\022..mavsdk.rpc.camera.SubscribeCap" + "tureInfoRequest\032&.mavsdk.rpc.camera.Capt" + "ureInfoResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStat" + "us\022).mavsdk.rpc.camera.SubscribeStatusRe" + "quest\032!.mavsdk.rpc.camera.StatusResponse" + "\"\0000\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavs" + "dk.rpc.camera.SubscribeCurrentSettingsRe" + "quest\032*.mavsdk.rpc.camera.CurrentSetting" + "sResponse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleS" + "ettingOptions\0229.mavsdk.rpc.camera.Subscr" + "ibePossibleSettingOptionsRequest\0321.mavsd" + "k.rpc.camera.PossibleSettingOptionsRespo" + "nse\"\0000\001\022[\n\nSetSetting\022$.mavsdk.rpc.camer" + "a.SetSettingRequest\032%.mavsdk.rpc.camera." + "SetSettingResponse\"\000\022[\n\nGetSetting\022$.mav" + "sdk.rpc.camera.GetSettingRequest\032%.mavsd" + "k.rpc.camera.GetSettingResponse\"\000\022d\n\rFor" + "matStorage\022\'.mavsdk.rpc.camera.FormatSto" + "rageRequest\032(.mavsdk.rpc.camera.FormatSt" + "orageResponse\"\000\022e\n\014SelectCamera\022&.mavsdk" + ".rpc.camera.SelectCameraRequest\032\'.mavsdk" + ".rpc.camera.SelectCameraResponse\"\004\200\265\030\001\022d" + "\n\rResetSettings\022\'.mavsdk.rpc.camera.Rese" + "tSettingsRequest\032(.mavsdk.rpc.camera.Res" + "etSettingsResponse\"\000B\037\n\020io.mavsdk.camera" + "B\013CameraProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -1841,13 +1902,13 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 7714, + 7941, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, descriptor_table_camera_2fcamera_2eproto_deps, 1, - 54, + 56, schemas, file_default_instances, TableStruct_camera_2fcamera_2eproto::offsets, @@ -7717,31 +7778,167 @@ class FormatStorageRequest::_Internal { }; FormatStorageRequest::FormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FormatStorageRequest) } FormatStorageRequest::FormatStorageRequest(const FormatStorageRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - FormatStorageRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FormatStorageRequest) } +inline void FormatStorageRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.storage_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +FormatStorageRequest::~FormatStorageRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FormatStorageRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void FormatStorageRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void FormatStorageRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void FormatStorageRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FormatStorageRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.storage_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* FormatStorageRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 storage_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* FormatStorageRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FormatStorageRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_storage_id(), target); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera.FormatStorageRequest) + return target; +} + +::size_t FormatStorageRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FormatStorageRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} const ::PROTOBUF_NAMESPACE_ID::Message::ClassData FormatStorageRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + FormatStorageRequest::MergeImpl }; const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*FormatStorageRequest::GetClassData() const { return &_class_data_; } +void FormatStorageRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera.FormatStorageRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} +void FormatStorageRequest::CopyFrom(const FormatStorageRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FormatStorageRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +bool FormatStorageRequest::IsInitialized() const { + return true; +} +void FormatStorageRequest::InternalSwap(FormatStorageRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.storage_id_, other->_impl_.storage_id_); +} ::PROTOBUF_NAMESPACE_ID::Metadata FormatStorageRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( @@ -8334,6 +8531,249 @@ ::PROTOBUF_NAMESPACE_ID::Metadata SelectCameraRequest::GetMetadata() const { } // =================================================================== +class ResetSettingsRequest::_Internal { + public: +}; + +ResetSettingsRequest::ResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsRequest) +} +ResetSettingsRequest::ResetSettingsRequest(const ResetSettingsRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + ResetSettingsRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ResetSettingsRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ResetSettingsRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ResetSettingsRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata ResetSettingsRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[42]); +} +// =================================================================== + +class ResetSettingsResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ResetSettingsResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& +ResetSettingsResponse::_Internal::camera_result(const ResetSettingsResponse* msg) { + return *msg->_impl_.camera_result_; +} +ResetSettingsResponse::ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsResponse) +} +ResetSettingsResponse::ResetSettingsResponse(const ResetSettingsResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + ResetSettingsResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_result_ = new ::mavsdk::rpc::camera::CameraResult(*from._impl_.camera_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ResetSettingsResponse) +} + +inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_result_){nullptr} + }; +} + +ResetSettingsResponse::~ResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ResetSettingsResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void ResetSettingsResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_result_; +} + +void ResetSettingsResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void ResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_result_ != nullptr); + _impl_.camera_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ResetSettingsResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* ResetSettingsResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_result(this), + _Internal::camera_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera.ResetSettingsResponse) + return target; +} + +::size_t ResetSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ResetSettingsResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ResetSettingsResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + ResetSettingsResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ResetSettingsResponse::GetClassData() const { return &_class_data_; } + + +void ResetSettingsResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera.ResetSettingsResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( + from._internal_camera_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ResetSettingsResponse::CopyFrom(const ResetSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ResetSettingsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ResetSettingsResponse::IsInitialized() const { + return true; +} + +void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_result_, other->_impl_.camera_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ResetSettingsResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[43]); +} +// =================================================================== + class CameraResult::_Internal { public: }; @@ -8559,7 +8999,7 @@ void CameraResult::InternalSwap(CameraResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[42]); + file_level_metadata_camera_2fcamera_2eproto[44]); } // =================================================================== @@ -8864,7 +9304,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[43]); + file_level_metadata_camera_2fcamera_2eproto[45]); } // =================================================================== @@ -9169,7 +9609,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[44]); + file_level_metadata_camera_2fcamera_2eproto[46]); } // =================================================================== @@ -9436,7 +9876,7 @@ void EulerAngle::InternalSwap(EulerAngle* other) { ::PROTOBUF_NAMESPACE_ID::Metadata EulerAngle::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[45]); + file_level_metadata_camera_2fcamera_2eproto[47]); } // =================================================================== @@ -9884,7 +10324,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[46]); + file_level_metadata_camera_2fcamera_2eproto[48]); } // =================================================================== @@ -10288,7 +10728,7 @@ void VideoStreamSettings::InternalSwap(VideoStreamSettings* other) { ::PROTOBUF_NAMESPACE_ID::Metadata VideoStreamSettings::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[47]); + file_level_metadata_camera_2fcamera_2eproto[49]); } // =================================================================== @@ -10564,7 +11004,7 @@ void VideoStreamInfo::InternalSwap(VideoStreamInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata VideoStreamInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[48]); + file_level_metadata_camera_2fcamera_2eproto[50]); } // =================================================================== @@ -11077,7 +11517,7 @@ void Status::InternalSwap(Status* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Status::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[49]); + file_level_metadata_camera_2fcamera_2eproto[51]); } // =================================================================== @@ -11320,7 +11760,7 @@ void Option::InternalSwap(Option* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Option::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[50]); + file_level_metadata_camera_2fcamera_2eproto[52]); } // =================================================================== @@ -11656,7 +12096,7 @@ void Setting::InternalSwap(Setting* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Setting::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[51]); + file_level_metadata_camera_2fcamera_2eproto[53]); } // =================================================================== @@ -11966,7 +12406,7 @@ void SettingOptions::InternalSwap(SettingOptions* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SettingOptions::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[52]); + file_level_metadata_camera_2fcamera_2eproto[54]); } // =================================================================== @@ -12399,7 +12839,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[53]); + file_level_metadata_camera_2fcamera_2eproto[55]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera @@ -12574,6 +13014,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera::SelectCameraRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera::SelectCameraRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera::SelectCameraRequest >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera::ResetSettingsRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera::ResetSettingsRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera::ResetSettingsRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera::ResetSettingsResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera::ResetSettingsResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera::ResetSettingsResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera::CameraResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera::CameraResult >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera::CameraResult >(arena); diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index f320b2a85b..a38247bbed 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -116,6 +116,12 @@ extern PrepareResponseDefaultTypeInternal _PrepareResponse_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +class ResetSettingsRequest; +struct ResetSettingsRequestDefaultTypeInternal; +extern ResetSettingsRequestDefaultTypeInternal _ResetSettingsRequest_default_instance_; +class ResetSettingsResponse; +struct ResetSettingsResponseDefaultTypeInternal; +extern ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; class SelectCameraRequest; struct SelectCameraRequestDefaultTypeInternal; extern SelectCameraRequestDefaultTypeInternal _SelectCameraRequest_default_instance_; @@ -263,6 +269,10 @@ ::mavsdk::rpc::camera::PrepareResponse* Arena::CreateMaybeMessage<::mavsdk::rpc: template <> ::mavsdk::rpc::camera::Quaternion* Arena::CreateMaybeMessage<::mavsdk::rpc::camera::Quaternion>(Arena*); template <> +::mavsdk::rpc::camera::ResetSettingsRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera::ResetSettingsRequest>(Arena*); +template <> +::mavsdk::rpc::camera::ResetSettingsResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera::ResetSettingsResponse>(Arena*); +template <> ::mavsdk::rpc::camera::SelectCameraRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera::SelectCameraRequest>(Arena*); template <> ::mavsdk::rpc::camera::SelectCameraResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera::SelectCameraResponse>(Arena*); @@ -6242,9 +6252,10 @@ class GetSettingResponse final : };// ------------------------------------------------------------------- class FormatStorageRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.FormatStorageRequest) */ { + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.FormatStorageRequest) */ { public: inline FormatStorageRequest() : FormatStorageRequest(nullptr) {} + ~FormatStorageRequest() override; template explicit PROTOBUF_CONSTEXPR FormatStorageRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); @@ -6325,15 +6336,29 @@ class FormatStorageRequest final : FormatStorageRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const FormatStorageRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const FormatStorageRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const FormatStorageRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const FormatStorageRequest& from) { + FormatStorageRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(FormatStorageRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; @@ -6353,6 +6378,19 @@ class FormatStorageRequest final : // accessors ------------------------------------------------------- + enum : int { + kStorageIdFieldNumber = 1, + }; + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); + + private: + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.FormatStorageRequest) private: class _Internal; @@ -6361,7 +6399,10 @@ class FormatStorageRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + ::int32_t storage_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -6840,6 +6881,290 @@ class SelectCameraRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- +class ResetSettingsRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ResetSettingsRequest) */ { + public: + inline ResetSettingsRequest() : ResetSettingsRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR ResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ResetSettingsRequest(const ResetSettingsRequest& from); + ResetSettingsRequest(ResetSettingsRequest&& from) noexcept + : ResetSettingsRequest() { + *this = ::std::move(from); + } + + inline ResetSettingsRequest& operator=(const ResetSettingsRequest& from) { + CopyFrom(from); + return *this; + } + inline ResetSettingsRequest& operator=(ResetSettingsRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 ResetSettingsRequest& default_instance() { + return *internal_default_instance(); + } + static inline const ResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 42; + + friend void swap(ResetSettingsRequest& a, ResetSettingsRequest& b) { + a.Swap(&b); + } + inline void Swap(ResetSettingsRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ResetSettingsRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ResetSettingsRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const ResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const ResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera.ResetSettingsRequest"; + } + protected: + explicit ResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ResetSettingsRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_2fcamera_2eproto; +};// ------------------------------------------------------------------- + +class ResetSettingsResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ResetSettingsResponse) */ { + public: + inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} + ~ResetSettingsResponse() override; + template + explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ResetSettingsResponse(const ResetSettingsResponse& from); + ResetSettingsResponse(ResetSettingsResponse&& from) noexcept + : ResetSettingsResponse() { + *this = ::std::move(from); + } + + inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { + CopyFrom(from); + return *this; + } + inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 ResetSettingsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 43; + + friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { + a.Swap(&b); + } + inline void Swap(ResetSettingsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ResetSettingsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ResetSettingsResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ResetSettingsResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const ResetSettingsResponse& from) { + ResetSettingsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ResetSettingsResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera.ResetSettingsResponse"; + } + protected: + explicit ResetSettingsResponse(::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 { + kCameraResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + bool has_camera_result() const; + void clear_camera_result() ; + const ::mavsdk::rpc::camera::CameraResult& camera_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera::CameraResult* release_camera_result(); + ::mavsdk::rpc::camera::CameraResult* mutable_camera_result(); + void set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* camera_result); + private: + const ::mavsdk::rpc::camera::CameraResult& _internal_camera_result() const; + ::mavsdk::rpc::camera::CameraResult* _internal_mutable_camera_result(); + public: + void unsafe_arena_set_allocated_camera_result( + ::mavsdk::rpc::camera::CameraResult* camera_result); + ::mavsdk::rpc::camera::CameraResult* unsafe_arena_release_camera_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ResetSettingsResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera::CameraResult* camera_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_2fcamera_2eproto; +};// ------------------------------------------------------------------- + class CameraResult final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.CameraResult) */ { public: @@ -6896,7 +7221,7 @@ class CameraResult final : &_CameraResult_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 44; friend void swap(CameraResult& a, CameraResult& b) { a.Swap(&b); @@ -7101,7 +7426,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 43; + 45; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -7292,7 +7617,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 44; + 46; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -7483,7 +7808,7 @@ class EulerAngle final : &_EulerAngle_default_instance_); } static constexpr int kIndexInFileMessages = - 45; + 47; friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); @@ -7662,7 +7987,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 48; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -7912,7 +8237,7 @@ class VideoStreamSettings final : &_VideoStreamSettings_default_instance_); } static constexpr int kIndexInFileMessages = - 47; + 49; friend void swap(VideoStreamSettings& a, VideoStreamSettings& b) { a.Swap(&b); @@ -8149,7 +8474,7 @@ class VideoStreamInfo final : &_VideoStreamInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 50; friend void swap(VideoStreamInfo& a, VideoStreamInfo& b) { a.Swap(&b); @@ -8374,7 +8699,7 @@ class Status final : &_Status_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 51; friend void swap(Status& a, Status& b) { a.Swap(&b); @@ -8693,7 +9018,7 @@ class Option final : &_Option_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 52; friend void swap(Option& a, Option& b) { a.Swap(&b); @@ -8880,7 +9205,7 @@ class Setting final : &_Setting_default_instance_); } static constexpr int kIndexInFileMessages = - 51; + 53; friend void swap(Setting& a, Setting& b) { a.Swap(&b); @@ -9096,7 +9421,7 @@ class SettingOptions final : &_SettingOptions_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 54; friend void swap(SettingOptions& a, SettingOptions& b) { a.Swap(&b); @@ -9317,7 +9642,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 53; + 55; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -11593,6 +11918,26 @@ inline void GetSettingResponse::set_allocated_setting(::mavsdk::rpc::camera::Set // FormatStorageRequest +// int32 storage_id = 1; +inline void FormatStorageRequest::clear_storage_id() { + _impl_.storage_id_ = 0; +} +inline ::int32_t FormatStorageRequest::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.FormatStorageRequest.storage_id) + return _internal_storage_id(); +} +inline void FormatStorageRequest::set_storage_id(::int32_t value) { + _internal_set_storage_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera.FormatStorageRequest.storage_id) +} +inline ::int32_t FormatStorageRequest::_internal_storage_id() const { + return _impl_.storage_id_; +} +inline void FormatStorageRequest::_internal_set_storage_id(::int32_t value) { + ; + _impl_.storage_id_ = value; +} + // ------------------------------------------------------------------- // FormatStorageResponse @@ -11801,6 +12146,101 @@ inline void SelectCameraRequest::_internal_set_camera_id(::int32_t value) { // ------------------------------------------------------------------- +// ResetSettingsRequest + +// ------------------------------------------------------------------- + +// ResetSettingsResponse + +// .mavsdk.rpc.camera.CameraResult camera_result = 1; +inline bool ResetSettingsResponse::has_camera_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_result_ != nullptr); + return value; +} +inline void ResetSettingsResponse::clear_camera_result() { + if (_impl_.camera_result_ != nullptr) _impl_.camera_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera::CameraResult& ResetSettingsResponse::_internal_camera_result() const { + const ::mavsdk::rpc::camera::CameraResult* p = _impl_.camera_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera::_CameraResult_default_instance_); +} +inline const ::mavsdk::rpc::camera::CameraResult& ResetSettingsResponse::camera_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.ResetSettingsResponse.camera_result) + return _internal_camera_result(); +} +inline void ResetSettingsResponse::unsafe_arena_set_allocated_camera_result( + ::mavsdk::rpc::camera::CameraResult* camera_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_result_); + } + _impl_.camera_result_ = camera_result; + if (camera_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera.ResetSettingsResponse.camera_result) +} +inline ::mavsdk::rpc::camera::CameraResult* ResetSettingsResponse::release_camera_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera::CameraResult* temp = _impl_.camera_result_; + _impl_.camera_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::camera::CameraResult* ResetSettingsResponse::unsafe_arena_release_camera_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.ResetSettingsResponse.camera_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera::CameraResult* temp = _impl_.camera_result_; + _impl_.camera_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera::CameraResult* ResetSettingsResponse::_internal_mutable_camera_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(GetArenaForAllocation()); + _impl_.camera_result_ = p; + } + return _impl_.camera_result_; +} +inline ::mavsdk::rpc::camera::CameraResult* ResetSettingsResponse::mutable_camera_result() { + ::mavsdk::rpc::camera::CameraResult* _msg = _internal_mutable_camera_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.ResetSettingsResponse.camera_result) + return _msg; +} +inline void ResetSettingsResponse::set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* camera_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_result_; + } + if (camera_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_result); + if (message_arena != submessage_arena) { + camera_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_result_ = camera_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.ResetSettingsResponse.camera_result) +} + +// ------------------------------------------------------------------- + // CameraResult // .mavsdk.rpc.camera.CameraResult.Result result = 1; diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index 6b2ce6ac87..cfae56f5e7 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -37,6 +37,8 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus", "/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage", + "/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -59,6 +61,8 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeFormatStorage_(CameraServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -304,6 +308,38 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureS return result; } +::grpc::ClientReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* CameraServerService::Stub::SubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::FormatStorageResponse>::Create(channel_.get(), rpcmethod_SubscribeFormatStorage_, context, request); +} + +void CameraServerService::Stub::async::SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::FormatStorageResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeFormatStorage_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* CameraServerService::Stub::AsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::FormatStorageResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFormatStorage_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* CameraServerService::Stub::PrepareAsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::FormatStorageResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFormatStorage_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* CameraServerService::Stub::SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(channel_.get(), rpcmethod_SubscribeResetSettings_, context, request); +} + +void CameraServerService::Stub::async::SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeResetSettings_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* CameraServerService::Stub::AsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeResetSettings_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* CameraServerService::Stub::PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeResetSettings_, context, request, false, nullptr); +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -435,6 +471,26 @@ CameraServerService::Service::Service() { ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* resp) { return service->RespondCaptureStatus(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[13], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::FormatStorageResponse>* writer) { + return service->SubscribeFormatStorage(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[14], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer) { + return service->SubscribeResetSettings(ctx, req, writer); + }, this))); } CameraServerService::Service::~Service() { @@ -531,6 +587,20 @@ ::grpc::Status CameraServerService::Service::RespondCaptureStatus(::grpc::Server return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SubscribeFormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraServerService::Service::SubscribeResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index d30f7e9746..20bcff1828 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -158,6 +158,26 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> PrepareAsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(PrepareAsyncRespondCaptureStatusRaw(context, request, cq)); } + // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>> SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(SubscribeFormatStorageRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>> AsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(AsyncSubscribeFormatStorageRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>> PrepareAsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(PrepareAsyncSubscribeFormatStorageRaw(context, request, cq)); + } + // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(SubscribeResetSettingsRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> AsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(AsyncSubscribeResetSettingsRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> PrepareAsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(PrepareAsyncSubscribeResetSettingsRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -192,6 +212,10 @@ class CameraServerService final { // Respond to camera capture status from SubscribeCaptureStatus. virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) = 0; virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + virtual void SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* reactor) = 0; + // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + virtual void SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -231,6 +255,12 @@ class CameraServerService final { virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* PrepareAsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* AsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* PrepareAsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* SubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* AsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* PrepareAsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* AsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -342,6 +372,24 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> PrepareAsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(PrepareAsyncRespondCaptureStatusRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>> SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(SubscribeFormatStorageRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>> AsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(AsyncSubscribeFormatStorageRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>> PrepareAsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(PrepareAsyncSubscribeFormatStorageRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(SubscribeResetSettingsRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> AsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(AsyncSubscribeResetSettingsRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> PrepareAsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(PrepareAsyncSubscribeResetSettingsRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -363,6 +411,8 @@ class CameraServerService final { void SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* reactor) override; void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) override; void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* reactor) override; + void SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -408,6 +458,12 @@ class CameraServerService final { ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* PrepareAsyncSubscribeCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* AsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* PrepareAsyncRespondCaptureStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* SubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* AsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* PrepareAsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* AsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; @@ -421,6 +477,8 @@ class CameraServerService final { const ::grpc::internal::RpcMethod rpcmethod_RespondStorageInformation_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCaptureStatus_; const ::grpc::internal::RpcMethod rpcmethod_RespondCaptureStatus_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeFormatStorage_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeResetSettings_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -454,6 +512,10 @@ class CameraServerService final { virtual ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer); // Respond to camera capture status from SubscribeCaptureStatus. virtual ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response); + // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + virtual ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer); + // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + virtual ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -715,7 +777,47 @@ class CameraServerService final { ::grpc::Service::RequestAsyncUnary(12, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodAsync(13); + } + ~WithAsyncMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodAsync(14); + } + ~WithAsyncMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -1027,7 +1129,51 @@ class CameraServerService final { virtual ::grpc::ServerUnaryReactor* RespondCaptureStatus( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > CallbackService; + template + class WithCallbackMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodCallback(13, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request) { return this->SubscribeFormatStorage(context, request); })); + } + ~WithCallbackMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* SubscribeFormatStorage( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodCallback(14, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request) { return this->SubscribeResetSettings(context, request); })); + } + ~WithCallbackMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -1251,6 +1397,40 @@ class CameraServerService final { } }; template + class WithGenericMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodGeneric(13); + } + ~WithGenericMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodGeneric(14); + } + ~WithGenericMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1511,6 +1691,46 @@ class CameraServerService final { } }; template + class WithRawMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodRaw(13); + } + ~WithRawMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodRaw(14); + } + ~WithRawMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1797,6 +2017,50 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodRawCallback(13, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFormatStorage(context, request); })); + } + ~WithRawCallbackMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeFormatStorage( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodRawCallback(14, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeResetSettings(context, request); })); + } + ~WithRawCallbackMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2148,8 +2412,62 @@ class CameraServerService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeCaptureStatus(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest,::mavsdk::rpc::camera_server::CaptureStatusResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeFormatStorage() { + ::grpc::Service::MarkMethodStreamed(13, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>* streamer) { + return this->StreamedSubscribeFormatStorage(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeFormatStorage(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest,::mavsdk::rpc::camera_server::FormatStorageResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeResetSettings() { + ::grpc::Service::MarkMethodStreamed(14, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>* streamer) { + return this->StreamedSubscribeResetSettings(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest,::mavsdk::rpc::camera_server::ResetSettingsResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 88c28ad370..771d300e8d 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -382,6 +382,64 @@ struct RespondCaptureStatusResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondCaptureStatusResponseDefaultTypeInternal _RespondCaptureStatusResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest::SubscribeFormatStorageRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeFormatStorageRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeFormatStorageRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeFormatStorageRequestDefaultTypeInternal() {} + union { + SubscribeFormatStorageRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeFormatStorageRequestDefaultTypeInternal _SubscribeFormatStorageRequest_default_instance_; +template +PROTOBUF_CONSTEXPR FormatStorageResponse::FormatStorageResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.storage_id_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct FormatStorageResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR FormatStorageResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FormatStorageResponseDefaultTypeInternal() {} + union { + FormatStorageResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FormatStorageResponseDefaultTypeInternal _FormatStorageResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest::SubscribeResetSettingsRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeResetSettingsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeResetSettingsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeResetSettingsRequestDefaultTypeInternal() {} + union { + SubscribeResetSettingsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeResetSettingsRequestDefaultTypeInternal _SubscribeResetSettingsRequest_default_instance_; +template +PROTOBUF_CONSTEXPR ResetSettingsResponse::ResetSettingsResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.reserved_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct ResetSettingsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ResetSettingsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ResetSettingsResponseDefaultTypeInternal() {} + union { + ResetSettingsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; +template PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} @@ -609,7 +667,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[37]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -830,6 +888,40 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _impl_.camera_server_result_), 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, _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::camera_server::FormatStorageResponse, _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::camera_server::FormatStorageResponse, _impl_.storage_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, _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::camera_server::ResetSettingsResponse, _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::camera_server::ResetSettingsResponse, _impl_.reserved_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -983,15 +1075,19 @@ static const ::_pbi::MigrationSchema { 186, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, { 195, 204, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, { 205, 214, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, - { 215, 225, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 227, 236, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 237, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 256, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 268, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 280, 294, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 300, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, - { 310, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, - { 326, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, + { 215, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, + { 223, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, + { 232, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, + { 240, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, + { 249, 259, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 261, 270, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 271, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 290, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 302, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 314, 328, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 334, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 344, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + { 360, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1019,6 +1115,10 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_CaptureStatusResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondCaptureStatusRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondCaptureStatusResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeFormatStorageRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_FormatStorageResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SubscribeResetSettingsRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_ResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, @@ -1067,119 +1167,130 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "CaptureStatus\"j\n\034RespondCaptureStatusRes" "ponse\022J\n\024camera_server_result\030\001 \001(\0132,.ma" "vsdk.rpc.camera_server.CameraServerResul" - "t\"\240\001\n\027RespondTakePhotoRequest\022H\n\023take_ph" - "oto_feedback\030\001 \001(\0162+.mavsdk.rpc.camera_s" - "erver.TakePhotoFeedback\022;\n\014capture_info\030" - "\002 \001(\0132%.mavsdk.rpc.camera_server.Capture" - "Info\"f\n\030RespondTakePhotoResponse\022J\n\024came" - "ra_server_result\030\001 \001(\0132,.mavsdk.rpc.came" - "ra_server.CameraServerResult\"\276\002\n\013Informa" - "tion\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030" - "\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal" - "_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_si" - "ze_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006" - " \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r\022\036" - "\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens_i" - "d\030\t \001(\r\022\037\n\027definition_file_version\030\n \001(\r" - "\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Positio" - "n\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg" - "\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023r" - "elative_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t" - "\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001" - "(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".m" - "avsdk.rpc.camera_server.Position\022A\n\023atti" - "tude_quaternion\030\002 \001(\0132$.mavsdk.rpc.camer" - "a_server.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004" - "\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010f" - "ile_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006" - "result\030\001 \001(\01623.mavsdk.rpc.camera_server." - "CameraServerResult.Result\022\022\n\nresult_str\030" - "\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016" - "RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002" - "\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014" - "RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RE" - "SULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTE" - "M\020\010\"\214\005\n\022StorageInformation\022\030\n\020used_stora" - "ge_mib\030\001 \001(\002\022\035\n\025available_storage_mib\030\002 " - "\001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016storag" - "e_status\030\004 \001(\0162:.mavsdk.rpc.camera_serve" - "r.StorageInformation.StorageStatus\022\022\n\nst" - "orage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628.m" - "avsdk.rpc.camera_server.StorageInformati" - "on.StorageType\022\030\n\020read_speed_mib_s\030\007 \001(\002" - "\022\031\n\021write_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorageS" - "tatus\022 \n\034STORAGE_STATUS_NOT_AVAILABLE\020\000\022" - "\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STORA" - "GE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STATUS_" - "NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STORA" - "GE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_ST" - "ICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TY" - "PE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STO" - "RAGE_TYPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020" - "image_interval_s\030\001 \001(\002\022\030\n\020recording_time" - "_s\030\002 \001(\002\022\036\n\026available_capacity_mib\030\003 \001(\002" - "\022I\n\014image_status\030\004 \001(\01623.mavsdk.rpc.came" - "ra_server.CaptureStatus.ImageStatus\022I\n\014v" - "ideo_status\030\005 \001(\01623.mavsdk.rpc.camera_se" - "rver.CaptureStatus.VideoStatus\022\023\n\013image_" - "count\030\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_STA" - "TUS_IDLE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_PR" - "OGRESS\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE\020\002" - "\022%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\020\003\"" - "J\n\013VideoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n" - " VIDEO_STATUS_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021" - "TakePhotoFeedback\022\037\n\033TAKE_PHOTO_FEEDBACK" - "_UNKNOWN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034" - "\n\030TAKE_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHO" - "TO_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNK" - "NOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\226" - "\016\n\023CameraServerService\022y\n\016SetInformation" - "\022/.mavsdk.rpc.camera_server.SetInformati" - "onRequest\0320.mavsdk.rpc.camera_server.Set" - "InformationResponse\"\004\200\265\030\001\022v\n\rSetInProgre" - "ss\022..mavsdk.rpc.camera_server.SetInProgr" - "essRequest\032/.mavsdk.rpc.camera_server.Se" - "tInProgressResponse\"\004\200\265\030\001\022~\n\022SubscribeTa" - "kePhoto\0223.mavsdk.rpc.camera_server.Subsc" - "ribeTakePhotoRequest\032+.mavsdk.rpc.camera" - "_server.TakePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020Res" - "pondTakePhoto\0221.mavsdk.rpc.camera_server" - ".RespondTakePhotoRequest\0322.mavsdk.rpc.ca" - "mera_server.RespondTakePhotoResponse\"\004\200\265" - "\030\001\022\201\001\n\023SubscribeStartVideo\0224.mavsdk.rpc." - "camera_server.SubscribeStartVideoRequest" - "\032,.mavsdk.rpc.camera_server.StartVideoRe" - "sponse\"\004\200\265\030\0000\001\022~\n\022SubscribeStopVideo\0223.m" - "avsdk.rpc.camera_server.SubscribeStopVid" - "eoRequest\032+.mavsdk.rpc.camera_server.Sto" - "pVideoResponse\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStar" - "tVideoStreaming\022=.mavsdk.rpc.camera_serv" - "er.SubscribeStartVideoStreamingRequest\0325" - ".mavsdk.rpc.camera_server.StartVideoStre" - "amingResponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopV" - "ideoStreaming\022<.mavsdk.rpc.camera_server" - ".SubscribeStopVideoStreamingRequest\0324.ma" - "vsdk.rpc.camera_server.StopVideoStreamin" - "gResponse\"\004\200\265\030\0000\001\022x\n\020SubscribeSetMode\0221." - "mavsdk.rpc.camera_server.SubscribeSetMod" - "eRequest\032).mavsdk.rpc.camera_server.SetM" - "odeResponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorage" - "Information\022<.mavsdk.rpc.camera_server.S" - "ubscribeStorageInformationRequest\0324.mavs" - "dk.rpc.camera_server.StorageInformationR" - "esponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInform" - "ation\022:.mavsdk.rpc.camera_server.Respond" - "StorageInformationRequest\032;.mavsdk.rpc.c" - "amera_server.RespondStorageInformationRe" - "sponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\022" - "7.mavsdk.rpc.camera_server.SubscribeCapt" - "ureStatusRequest\032/.mavsdk.rpc.camera_ser" - "ver.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Re" - "spondCaptureStatus\0225.mavsdk.rpc.camera_s" - "erver.RespondCaptureStatusRequest\0326.mavs" - "dk.rpc.camera_server.RespondCaptureStatu" - "sResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera_serv" - "erB\021CameraServerProtob\006proto3" + "t\"\037\n\035SubscribeFormatStorageRequest\"+\n\025Fo" + "rmatStorageResponse\022\022\n\nstorage_id\030\001 \001(\005\"" + "\037\n\035SubscribeResetSettingsRequest\")\n\025Rese" + "tSettingsResponse\022\020\n\010reserved\030\001 \001(\005\"\240\001\n\027" + "RespondTakePhotoRequest\022H\n\023take_photo_fe" + "edback\030\001 \001(\0162+.mavsdk.rpc.camera_server." + "TakePhotoFeedback\022;\n\014capture_info\030\002 \001(\0132" + "%.mavsdk.rpc.camera_server.CaptureInfo\"f" + "\n\030RespondTakePhotoResponse\022J\n\024camera_ser" + "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" + "ver.CameraServerResult\"\276\002\n\013Information\022\023" + "\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022" + "\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal_lengt" + "h_mm\030\004 \001(\002\022!\n\031horizontal_sensor_size_mm\030" + "\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006 \001(\002\022 " + "\n\030horizontal_resolution_px\030\007 \001(\r\022\036\n\026vert" + "ical_resolution_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(" + "\r\022\037\n\027definition_file_version\030\n \001(\r\022\033\n\023de" + "finition_file_uri\030\013 \001(\t\"q\n\010Position\022\024\n\014l" + "atitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001" + "\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023relativ" + "e_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 " + "\001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n" + "\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".mavsdk." + "rpc.camera_server.Position\022A\n\023attitude_q" + "uaternion\030\002 \001(\0132$.mavsdk.rpc.camera_serv" + "er.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis" + "_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_ur" + "l\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006result" + "\030\001 \001(\01623.mavsdk.rpc.camera_server.Camera" + "ServerResult.Result\022\022\n\nresult_str\030\002 \001(\t\"" + "\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT" + "_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013RE" + "SULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESULT" + "_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT_W" + "RONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005" + "\n\022StorageInformation\022\030\n\020used_storage_mib" + "\030\001 \001(\002\022\035\n\025available_storage_mib\030\002 \001(\002\022\031\n" + "\021total_storage_mib\030\003 \001(\002\022R\n\016storage_stat" + "us\030\004 \001(\0162:.mavsdk.rpc.camera_server.Stor" + "ageInformation.StorageStatus\022\022\n\nstorage_" + "id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628.mavsdk." + "rpc.camera_server.StorageInformation.Sto" + "rageType\022\030\n\020read_speed_mib_s\030\007 \001(\002\022\031\n\021wr" + "ite_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022" + " \n\034STORAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STO" + "RAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STA" + "TUS_FORMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SU" + "PPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYP" + "E_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022" + "\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MIC" + "ROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_T" + "YPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020image_" + "interval_s\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001" + "(\002\022\036\n\026available_capacity_mib\030\003 \001(\002\022I\n\014im" + "age_status\030\004 \001(\01623.mavsdk.rpc.camera_ser" + "ver.CaptureStatus.ImageStatus\022I\n\014video_s" + "tatus\030\005 \001(\01623.mavsdk.rpc.camera_server.C" + "aptureStatus.VideoStatus\022\023\n\013image_count\030" + "\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_STATUS_ID" + "LE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_PROGRESS" + "\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE\020\002\022%\n!IM" + "AGE_STATUS_INTERVAL_IN_PROGRESS\020\003\"J\n\013Vid" + "eoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO" + "_STATUS_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021TakePh" + "otoFeedback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNO" + "WN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE" + "_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEE" + "DBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000" + "\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\260\020\n\023Cam" + "eraServerService\022y\n\016SetInformation\022/.mav" + "sdk.rpc.camera_server.SetInformationRequ" + "est\0320.mavsdk.rpc.camera_server.SetInform" + "ationResponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..m" + "avsdk.rpc.camera_server.SetInProgressReq" + "uest\032/.mavsdk.rpc.camera_server.SetInPro" + "gressResponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhot" + "o\0223.mavsdk.rpc.camera_server.SubscribeTa" + "kePhotoRequest\032+.mavsdk.rpc.camera_serve" + "r.TakePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTa" + "kePhoto\0221.mavsdk.rpc.camera_server.Respo" + "ndTakePhotoRequest\0322.mavsdk.rpc.camera_s" + "erver.RespondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n" + "\023SubscribeStartVideo\0224.mavsdk.rpc.camera" + "_server.SubscribeStartVideoRequest\032,.mav" + "sdk.rpc.camera_server.StartVideoResponse" + "\"\004\200\265\030\0000\001\022~\n\022SubscribeStopVideo\0223.mavsdk." + "rpc.camera_server.SubscribeStopVideoRequ" + "est\032+.mavsdk.rpc.camera_server.StopVideo" + "Response\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideo" + "Streaming\022=.mavsdk.rpc.camera_server.Sub" + "scribeStartVideoStreamingRequest\0325.mavsd" + "k.rpc.camera_server.StartVideoStreamingR" + "esponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoSt" + "reaming\022<.mavsdk.rpc.camera_server.Subsc" + "ribeStopVideoStreamingRequest\0324.mavsdk.r" + "pc.camera_server.StopVideoStreamingRespo" + "nse\"\004\200\265\030\0000\001\022x\n\020SubscribeSetMode\0221.mavsdk" + ".rpc.camera_server.SubscribeSetModeReque" + "st\032).mavsdk.rpc.camera_server.SetModeRes" + "ponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorageInform" + "ation\022<.mavsdk.rpc.camera_server.Subscri" + "beStorageInformationRequest\0324.mavsdk.rpc" + ".camera_server.StorageInformationRespons" + "e\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInformation\022" + ":.mavsdk.rpc.camera_server.RespondStorag" + "eInformationRequest\032;.mavsdk.rpc.camera_" + "server.RespondStorageInformationResponse" + "\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227.mavs" + "dk.rpc.camera_server.SubscribeCaptureSta" + "tusRequest\032/.mavsdk.rpc.camera_server.Ca" + "ptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondC" + "aptureStatus\0225.mavsdk.rpc.camera_server." + "RespondCaptureStatusRequest\0326.mavsdk.rpc" + ".camera_server.RespondCaptureStatusRespo" + "nse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorage\0227.m" + "avsdk.rpc.camera_server.SubscribeFormatS" + "torageRequest\032/.mavsdk.rpc.camera_server" + ".FormatStorageResponse\"\004\200\265\030\0000\001\022\212\001\n\026Subsc" + "ribeResetSettings\0227.mavsdk.rpc.camera_se" + "rver.SubscribeResetSettingsRequest\032/.mav" + "sdk.rpc.camera_server.ResetSettingsRespo" + "nse\"\004\200\265\030\0000\001B,\n\027io.mavsdk.camera_serverB\021" + "CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1189,13 +1300,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 5989, + 6425, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 33, + 37, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -4709,6 +4820,430 @@ ::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusResponse::GetMetadata() co } // =================================================================== +class SubscribeFormatStorageRequest::_Internal { + public: +}; + +SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) +} +SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeFormatStorageRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeFormatStorageRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeFormatStorageRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeFormatStorageRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); +} +// =================================================================== + +class FormatStorageResponse::_Internal { + public: +}; + +FormatStorageResponse::FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) +} +FormatStorageResponse::FormatStorageResponse(const FormatStorageResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) +} + +inline void FormatStorageResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.storage_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +FormatStorageResponse::~FormatStorageResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.FormatStorageResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void FormatStorageResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void FormatStorageResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void FormatStorageResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.FormatStorageResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.storage_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* FormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 storage_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* FormatStorageResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.FormatStorageResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_storage_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.FormatStorageResponse) + return target; +} + +::size_t FormatStorageResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.FormatStorageResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData FormatStorageResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + FormatStorageResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*FormatStorageResponse::GetClassData() const { return &_class_data_; } + + +void FormatStorageResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.FormatStorageResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void FormatStorageResponse::CopyFrom(const FormatStorageResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.FormatStorageResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool FormatStorageResponse::IsInitialized() const { + return true; +} + +void FormatStorageResponse::InternalSwap(FormatStorageResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.storage_id_, other->_impl_.storage_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata FormatStorageResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); +} +// =================================================================== + +class SubscribeResetSettingsRequest::_Internal { + public: +}; + +SubscribeResetSettingsRequest::SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) +} +SubscribeResetSettingsRequest::SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeResetSettingsRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeResetSettingsRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeResetSettingsRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeResetSettingsRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); +} +// =================================================================== + +class ResetSettingsResponse::_Internal { + public: +}; + +ResetSettingsResponse::ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.ResetSettingsResponse) +} +ResetSettingsResponse::ResetSettingsResponse(const ResetSettingsResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.ResetSettingsResponse) +} + +inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.reserved_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +ResetSettingsResponse::~ResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.ResetSettingsResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void ResetSettingsResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void ResetSettingsResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void ResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.reserved_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ResetSettingsResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 reserved = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.reserved_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* ResetSettingsResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_reserved(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.ResetSettingsResponse) + return target; +} + +::size_t ResetSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ResetSettingsResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + ResetSettingsResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ResetSettingsResponse::GetClassData() const { return &_class_data_; } + + +void ResetSettingsResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.ResetSettingsResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ResetSettingsResponse::CopyFrom(const ResetSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.ResetSettingsResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ResetSettingsResponse::IsInitialized() const { + return true; +} + +void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ResetSettingsResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); +} +// =================================================================== + class RespondTakePhotoRequest::_Internal { public: using HasBits = decltype(std::declval()._impl_._has_bits_); @@ -4947,7 +5482,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); } // =================================================================== @@ -5152,7 +5687,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); } // =================================================================== @@ -5737,7 +6272,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); } // =================================================================== @@ -6042,7 +6577,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); } // =================================================================== @@ -6347,7 +6882,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); } // =================================================================== @@ -6750,7 +7285,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]); } // =================================================================== @@ -6979,7 +7514,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[34]); } // =================================================================== @@ -7405,7 +7940,7 @@ void StorageInformation::InternalSwap(StorageInformation* other) { ::PROTOBUF_NAMESPACE_ID::Metadata StorageInformation::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[35]); } // =================================================================== @@ -7755,7 +8290,7 @@ void CaptureStatus::InternalSwap(CaptureStatus* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[36]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -7858,6 +8393,22 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondCaptureStatusR Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::FormatStorageResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::FormatStorageResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::FormatStorageResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::ResetSettingsResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::ResetSettingsResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::ResetSettingsResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index b8f07f46cf..914991c3d6 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -68,6 +68,9 @@ extern CaptureStatusDefaultTypeInternal _CaptureStatus_default_instance_; class CaptureStatusResponse; struct CaptureStatusResponseDefaultTypeInternal; extern CaptureStatusResponseDefaultTypeInternal _CaptureStatusResponse_default_instance_; +class FormatStorageResponse; +struct FormatStorageResponseDefaultTypeInternal; +extern FormatStorageResponseDefaultTypeInternal _FormatStorageResponse_default_instance_; class Information; struct InformationDefaultTypeInternal; extern InformationDefaultTypeInternal _Information_default_instance_; @@ -77,6 +80,9 @@ extern PositionDefaultTypeInternal _Position_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +class ResetSettingsResponse; +struct ResetSettingsResponseDefaultTypeInternal; +extern ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; class RespondCaptureStatusRequest; struct RespondCaptureStatusRequestDefaultTypeInternal; extern RespondCaptureStatusRequestDefaultTypeInternal _RespondCaptureStatusRequest_default_instance_; @@ -131,6 +137,12 @@ extern StorageInformationResponseDefaultTypeInternal _StorageInformationResponse class SubscribeCaptureStatusRequest; struct SubscribeCaptureStatusRequestDefaultTypeInternal; extern SubscribeCaptureStatusRequestDefaultTypeInternal _SubscribeCaptureStatusRequest_default_instance_; +class SubscribeFormatStorageRequest; +struct SubscribeFormatStorageRequestDefaultTypeInternal; +extern SubscribeFormatStorageRequestDefaultTypeInternal _SubscribeFormatStorageRequest_default_instance_; +class SubscribeResetSettingsRequest; +struct SubscribeResetSettingsRequestDefaultTypeInternal; +extern SubscribeResetSettingsRequestDefaultTypeInternal _SubscribeResetSettingsRequest_default_instance_; class SubscribeSetModeRequest; struct SubscribeSetModeRequestDefaultTypeInternal; extern SubscribeSetModeRequestDefaultTypeInternal _SubscribeSetModeRequest_default_instance_; @@ -168,12 +180,16 @@ ::mavsdk::rpc::camera_server::CaptureStatus* Arena::CreateMaybeMessage<::mavsdk: template <> ::mavsdk::rpc::camera_server::CaptureStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureStatusResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::FormatStorageResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::FormatStorageResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(Arena*); template <> ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Position>(Arena*); template <> ::mavsdk::rpc::camera_server::Quaternion* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::Quaternion>(Arena*); template <> +::mavsdk::rpc::camera_server::ResetSettingsResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::ResetSettingsResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondCaptureStatusRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>(Arena*); @@ -210,6 +226,10 @@ ::mavsdk::rpc::camera_server::StorageInformationResponse* Arena::CreateMaybeMess template <> ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest>(Arena*); template <> +::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest>(Arena*); +template <> ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeSetModeRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeStartVideoRequest>(Arena*); @@ -3979,25 +3999,24 @@ class RespondCaptureStatusResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { +class SubscribeFormatStorageRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) */ { public: - inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} - ~RespondTakePhotoRequest() override; + inline SubscribeFormatStorageRequest() : SubscribeFormatStorageRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoRequest(const RespondTakePhotoRequest& from); - RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept - : RespondTakePhotoRequest() { + SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from); + SubscribeFormatStorageRequest(SubscribeFormatStorageRequest&& from) noexcept + : SubscribeFormatStorageRequest() { *this = ::std::move(from); } - inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + inline SubscribeFormatStorageRequest& operator=(const SubscribeFormatStorageRequest& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + inline SubscribeFormatStorageRequest& operator=(SubscribeFormatStorageRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4027,20 +4046,20 @@ class RespondTakePhotoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoRequest& default_instance() { + static const SubscribeFormatStorageRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoRequest_default_instance_); + static inline const SubscribeFormatStorageRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = 24; - friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoRequest* other) { + inline void Swap(SubscribeFormatStorageRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4053,7 +4072,7 @@ class RespondTakePhotoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + void UnsafeArenaSwap(SubscribeFormatStorageRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4061,40 +4080,26 @@ class RespondTakePhotoRequest final : // implements Message ---------------------------------------------- - RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeFormatStorageRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoRequest& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoRequest& from) { - RespondTakePhotoRequest::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeFormatStorageRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeFormatStorageRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + return "mavsdk.rpc.camera_server.SubscribeFormatStorageRequest"; } protected: - explicit RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4106,35 +4111,7 @@ class RespondTakePhotoRequest final : // accessors ------------------------------------------------------- - enum : int { - kCaptureInfoFieldNumber = 2, - kTakePhotoFeedbackFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - bool has_capture_info() const; - void clear_capture_info() ; - const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); - ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); - void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - private: - const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; - ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); - public: - void unsafe_arena_set_allocated_capture_info( - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - void clear_take_photo_feedback() ; - ::mavsdk::rpc::camera_server::TakePhotoFeedback take_photo_feedback() const; - void set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - private: - ::mavsdk::rpc::camera_server::TakePhotoFeedback _internal_take_photo_feedback() const; - void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) private: class _Internal; @@ -4142,34 +4119,29 @@ class RespondTakePhotoRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; - int take_photo_feedback_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { +class FormatStorageResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.FormatStorageResponse) */ { public: - inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} - ~RespondTakePhotoResponse() override; + inline FormatStorageResponse() : FormatStorageResponse(nullptr) {} + ~FormatStorageResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoResponse(const RespondTakePhotoResponse& from); - RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept - : RespondTakePhotoResponse() { + FormatStorageResponse(const FormatStorageResponse& from); + FormatStorageResponse(FormatStorageResponse&& from) noexcept + : FormatStorageResponse() { *this = ::std::move(from); } - inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + inline FormatStorageResponse& operator=(const FormatStorageResponse& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + inline FormatStorageResponse& operator=(FormatStorageResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4199,20 +4171,20 @@ class RespondTakePhotoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoResponse& default_instance() { + static const FormatStorageResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoResponse_default_instance_); + static inline const FormatStorageResponse* internal_default_instance() { + return reinterpret_cast( + &_FormatStorageResponse_default_instance_); } static constexpr int kIndexInFileMessages = 25; - friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoResponse* other) { + inline void Swap(FormatStorageResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4225,7 +4197,7 @@ class RespondTakePhotoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + void UnsafeArenaSwap(FormatStorageResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4233,14 +4205,14 @@ class RespondTakePhotoResponse final : // implements Message ---------------------------------------------- - RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FormatStorageResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoResponse& from); + void CopyFrom(const FormatStorageResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoResponse& from) { - RespondTakePhotoResponse::MergeImpl(*this, from); + void MergeFrom( const FormatStorageResponse& from) { + FormatStorageResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4258,15 +4230,15 @@ class RespondTakePhotoResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoResponse* other); + void InternalSwap(FormatStorageResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + return "mavsdk.rpc.camera_server.FormatStorageResponse"; } protected: - explicit RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4279,23 +4251,19 @@ class RespondTakePhotoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kStorageIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - bool has_camera_server_result() const; - void clear_camera_server_result() ; - const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); - ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); - void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); + private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); + public: - void unsafe_arena_set_allocated_camera_server_result( - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); - ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.FormatStorageResponse) private: class _Internal; @@ -4303,33 +4271,31 @@ class RespondTakePhotoResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + ::int32_t storage_id_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Information final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { +class SubscribeResetSettingsRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) */ { public: - inline Information() : Information(nullptr) {} - ~Information() override; + inline SubscribeResetSettingsRequest() : SubscribeResetSettingsRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Information(const Information& from); - Information(Information&& from) noexcept - : Information() { + SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from); + SubscribeResetSettingsRequest(SubscribeResetSettingsRequest&& from) noexcept + : SubscribeResetSettingsRequest() { *this = ::std::move(from); } - inline Information& operator=(const Information& from) { + inline SubscribeResetSettingsRequest& operator=(const SubscribeResetSettingsRequest& from) { CopyFrom(from); return *this; } - inline Information& operator=(Information&& from) noexcept { + inline SubscribeResetSettingsRequest& operator=(SubscribeResetSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4359,20 +4325,20 @@ class Information final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Information& default_instance() { + static const SubscribeResetSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const Information* internal_default_instance() { - return reinterpret_cast( - &_Information_default_instance_); + static inline const SubscribeResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = 26; - friend void swap(Information& a, Information& b) { + friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { a.Swap(&b); } - inline void Swap(Information* other) { + inline void Swap(SubscribeResetSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4385,7 +4351,7 @@ class Information final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Information* other) { + void UnsafeArenaSwap(SubscribeResetSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4393,40 +4359,26 @@ class Information final : // implements Message ---------------------------------------------- - Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeResetSettingsRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Information& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Information& from) { - Information::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(Information* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Information"; + return "mavsdk.rpc.camera_server.SubscribeResetSettingsRequest"; } protected: - explicit Information(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4438,37 +4390,663 @@ class Information final : // accessors ------------------------------------------------------- - enum : int { - kVendorNameFieldNumber = 1, - kModelNameFieldNumber = 2, - kFirmwareVersionFieldNumber = 3, - kDefinitionFileUriFieldNumber = 11, - kFocalLengthMmFieldNumber = 4, - kHorizontalSensorSizeMmFieldNumber = 5, - kVerticalSensorSizeMmFieldNumber = 6, - kHorizontalResolutionPxFieldNumber = 7, - kVerticalResolutionPxFieldNumber = 8, - kLensIdFieldNumber = 9, - kDefinitionFileVersionFieldNumber = 10, + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { }; - // string vendor_name = 1; - void clear_vendor_name() ; - const std::string& vendor_name() const; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- +class ResetSettingsResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ResetSettingsResponse) */ { + public: + inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} + ~ResetSettingsResponse() override; + template + explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + ResetSettingsResponse(const ResetSettingsResponse& from); + ResetSettingsResponse(ResetSettingsResponse&& from) noexcept + : ResetSettingsResponse() { + *this = ::std::move(from); + } + inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { + CopyFrom(from); + return *this; + } + inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } - template - void set_vendor_name(Arg_&& arg, Args_... args); - std::string* mutable_vendor_name(); - PROTOBUF_NODISCARD std::string* release_vendor_name(); - void set_allocated_vendor_name(std::string* ptr); + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } - private: - const std::string& _internal_vendor_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( - const std::string& value); - std::string* _internal_mutable_vendor_name(); + 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 ResetSettingsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 27; + + friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { + a.Swap(&b); + } + inline void Swap(ResetSettingsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ResetSettingsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ResetSettingsResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ResetSettingsResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const ResetSettingsResponse& from) { + ResetSettingsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ResetSettingsResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.ResetSettingsResponse"; + } + protected: + explicit ResetSettingsResponse(::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 { + kReservedFieldNumber = 1, + }; + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); + + private: + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ResetSettingsResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t reserved_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondTakePhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { + public: + inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} + ~RespondTakePhotoRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondTakePhotoRequest(const RespondTakePhotoRequest& from); + RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept + : RespondTakePhotoRequest() { + *this = ::std::move(from); + } + + inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondTakePhotoRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 28; + + friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoRequest& from) { + RespondTakePhotoRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondTakePhotoRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + } + protected: + explicit RespondTakePhotoRequest(::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 { + kCaptureInfoFieldNumber = 2, + kTakePhotoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + bool has_capture_info() const; + void clear_capture_info() ; + const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); + ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); + void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + private: + const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; + ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); + public: + void unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); + // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + void clear_take_photo_feedback() ; + ::mavsdk::rpc::camera_server::TakePhotoFeedback take_photo_feedback() const; + void set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); + + private: + ::mavsdk::rpc::camera_server::TakePhotoFeedback _internal_take_photo_feedback() const; + void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; + int take_photo_feedback_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondTakePhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { + public: + inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} + ~RespondTakePhotoResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondTakePhotoResponse(const RespondTakePhotoResponse& from); + RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept + : RespondTakePhotoResponse() { + *this = ::std::move(from); + } + + inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondTakePhotoResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondTakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 29; + + friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondTakePhotoResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoResponse& from) { + RespondTakePhotoResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondTakePhotoResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + } + protected: + explicit RespondTakePhotoResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Information final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { + public: + inline Information() : Information(nullptr) {} + ~Information() override; + template + explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Information(const Information& from); + Information(Information&& from) noexcept + : Information() { + *this = ::std::move(from); + } + + inline Information& operator=(const Information& from) { + CopyFrom(from); + return *this; + } + inline Information& operator=(Information&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Information& default_instance() { + return *internal_default_instance(); + } + static inline const Information* internal_default_instance() { + return reinterpret_cast( + &_Information_default_instance_); + } + static constexpr int kIndexInFileMessages = + 30; + + friend void swap(Information& a, Information& b) { + a.Swap(&b); + } + inline void Swap(Information* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Information* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Information& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Information& from) { + Information::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Information* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Information"; + } + protected: + explicit Information(::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 { + kVendorNameFieldNumber = 1, + kModelNameFieldNumber = 2, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, + }; + // string vendor_name = 1; + void clear_vendor_name() ; + const std::string& vendor_name() const; + + + + + template + void set_vendor_name(Arg_&& arg, Args_... args); + std::string* mutable_vendor_name(); + PROTOBUF_NODISCARD std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* ptr); + + private: + const std::string& _internal_vendor_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( + const std::string& value); + std::string* _internal_mutable_vendor_name(); public: // string model_name = 2; @@ -4682,7 +5260,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 27; + 31; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -4873,7 +5451,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 32; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -5064,7 +5642,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 29; + 33; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -5298,7 +5876,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 34; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -5502,7 +6080,7 @@ class StorageInformation final : &_StorageInformation_default_instance_); } static constexpr int kIndexInFileMessages = - 31; + 35; friend void swap(StorageInformation& a, StorageInformation& b) { a.Swap(&b); @@ -5787,7 +6365,7 @@ class CaptureStatus final : &_CaptureStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 36; friend void swap(CaptureStatus& a, CaptureStatus& b) { a.Swap(&b); @@ -6887,6 +7465,62 @@ inline void RespondCaptureStatusResponse::set_allocated_camera_server_result(::m // ------------------------------------------------------------------- +// SubscribeFormatStorageRequest + +// ------------------------------------------------------------------- + +// FormatStorageResponse + +// int32 storage_id = 1; +inline void FormatStorageResponse::clear_storage_id() { + _impl_.storage_id_ = 0; +} +inline ::int32_t FormatStorageResponse::storage_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) + return _internal_storage_id(); +} +inline void FormatStorageResponse::set_storage_id(::int32_t value) { + _internal_set_storage_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.FormatStorageResponse.storage_id) +} +inline ::int32_t FormatStorageResponse::_internal_storage_id() const { + return _impl_.storage_id_; +} +inline void FormatStorageResponse::_internal_set_storage_id(::int32_t value) { + ; + _impl_.storage_id_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeResetSettingsRequest + +// ------------------------------------------------------------------- + +// ResetSettingsResponse + +// int32 reserved = 1; +inline void ResetSettingsResponse::clear_reserved() { + _impl_.reserved_ = 0; +} +inline ::int32_t ResetSettingsResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) + return _internal_reserved(); +} +inline void ResetSettingsResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) +} +inline ::int32_t ResetSettingsResponse::_internal_reserved() const { + return _impl_.reserved_; +} +inline void ResetSettingsResponse::_internal_set_reserved(::int32_t value) { + ; + _impl_.reserved_ = value; +} + +// ------------------------------------------------------------------- + // RespondTakePhotoRequest // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; diff --git a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h index 71b5445184..1317804d64 100644 --- a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h @@ -1329,7 +1329,7 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { grpc::Status FormatStorage( grpc::ServerContext* /* context */, - const rpc::camera::FormatStorageRequest* /* request */, + const rpc::camera::FormatStorageRequest* request, rpc::camera::FormatStorageResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { @@ -1341,7 +1341,12 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->format_storage(); + if (request == nullptr) { + LogWarn() << "FormatStorage sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->format_storage(request->storage_id()); if (response != nullptr) { fillResponseWithResult(response, result); @@ -1378,6 +1383,29 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return grpc::Status::OK; } + grpc::Status ResetSettings( + grpc::ServerContext* /* context */, + const rpc::camera::ResetSettingsRequest* /* request */, + rpc::camera::ResetSettingsResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::Camera::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->reset_settings(); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index c0f7055ecf..c5e2b0a010 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -1058,6 +1058,88 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SubscribeFormatStorage( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::FormatStorageHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_format_storage( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t format_storage) { + rpc::camera_server::FormatStorageResponse rpc_response; + + rpc_response.set_storage_id(format_storage); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_format_storage(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeResetSettings( + grpc::ServerContext* /* context */, + const mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::CameraServer::ResetSettingsHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_reset_settings( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const int32_t reset_settings) { + rpc::camera_server::ResetSettingsResponse rpc_response; + + rpc_response.set_reserved(reset_settings); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_reset_settings(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); From 2d15978c0a3703fc1a09d611117f18fc0f07a37a Mon Sep 17 00:00:00 2001 From: tbago Date: Sat, 24 Jun 2023 14:53:41 +0800 Subject: [PATCH 08/25] camera server: add feedback for all camera server command --- examples/camera_server/camera_server.cpp | 38 +- src/integration_tests/camera_take_photo.cpp | 2 +- .../plugins/camera_server/camera_server.cpp | 67 +- .../camera_server/camera_server_impl.cpp | 319 +- .../camera_server/camera_server_impl.h | 33 +- .../plugins/camera_server/camera_server.h | 98 +- .../camera_server/camera_server.grpc.pb.cc | 332 +- .../camera_server/camera_server.grpc.pb.h | 1356 +++- .../camera_server/camera_server.pb.cc | 5845 +++++++++++--- .../camera_server/camera_server.pb.h | 7096 ++++++++++++----- .../camera_server_service_impl.h | 273 +- src/system_tests/camera_take_photo.cpp | 2 +- 12 files changed, 11942 insertions(+), 3519 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 03861656cd..c7d8fa4f20 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -88,7 +88,7 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) camera_server.set_in_progress(false); camera_server.respond_take_photo( - mavsdk::CameraServer::TakePhotoFeedback::Ok, + mavsdk::CameraServer::CameraFeedback::Ok, mavsdk::CameraServer::CaptureInfo{ .position = position, .attitude_quaternion = attitude, @@ -101,25 +101,32 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) is_capture_in_progress = false; }); - camera_server.subscribe_start_video([](int32_t stream_id) { + camera_server.subscribe_start_video([&camera_server](int32_t stream_id) { std::cout << "Start video record" << std::endl; is_recording_video = true; start_video_time = std::chrono::steady_clock::now(); + camera_server.respond_start_video(mavsdk::CameraServer::CameraFeedback::Ok); }); - camera_server.subscribe_stop_video([](int32_t stream_id) { + camera_server.subscribe_stop_video([&camera_server](int32_t stream_id) { std::cout << "Stop video record" << std::endl; is_recording_video = false; + camera_server.respond_stop_video(mavsdk::CameraServer::CameraFeedback::Ok); }); - camera_server.subscribe_start_video_streaming( - [](int32_t stream_id) { std::cout << "Start video streaming " << stream_id << std::endl; }); + camera_server.subscribe_start_video_streaming([&camera_server](int32_t stream_id) { + std::cout << "Start video streaming " << stream_id << std::endl; + camera_server.respond_start_video_streaming(mavsdk::CameraServer::CameraFeedback::Ok); + }); - camera_server.subscribe_stop_video_streaming( - [](int32_t stream_id) { std::cout << "Stop video streaming " << stream_id << std::endl; }); + camera_server.subscribe_stop_video_streaming([&camera_server](int32_t stream_id) { + std::cout << "Stop video streaming " << stream_id << std::endl; + camera_server.respond_stop_video_streaming(mavsdk::CameraServer::CameraFeedback::Ok); + }); - camera_server.subscribe_set_mode([](mavsdk::CameraServer::Mode mode) { + camera_server.subscribe_set_mode([&camera_server](mavsdk::CameraServer::Mode mode) { std::cout << "Set camera mode " << mode << std::endl; + camera_server.respond_set_mode(mavsdk::CameraServer::CameraFeedback::Ok); }); camera_server.subscribe_storage_information([&camera_server](int32_t storage_id) { @@ -134,7 +141,8 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) storage_information.storage_type = mavsdk::CameraServer::StorageInformation::StorageType::Microsd; - camera_server.respond_storage_information(storage_information); + camera_server.respond_storage_information( + mavsdk::CameraServer::CameraFeedback::Ok, storage_information); }); camera_server.subscribe_capture_status([&camera_server](int32_t reserved) { @@ -154,13 +162,17 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server) std::chrono::duration_cast(current_time - start_video_time) .count(); } - camera_server.respond_capture_status(capture_status); + camera_server.respond_capture_status( + mavsdk::CameraServer::CameraFeedback::Ok, capture_status); }); - camera_server.subscribe_format_storage([](int storage_id) { + camera_server.subscribe_format_storage([&camera_server](int storage_id) { std::cout << "format storage with id : " << storage_id << std::endl; + camera_server.respond_format_storage(mavsdk::CameraServer::CameraFeedback::Ok); }); - camera_server.subscribe_reset_settings( - [](int camera_id) { std::cout << "reset camera settings" << std::endl; }); + camera_server.subscribe_reset_settings([&camera_server](int camera_id) { + std::cout << "reset camera settings" << std::endl; + camera_server.respond_reset_settings(mavsdk::CameraServer::CameraFeedback::Ok); + }); } \ No newline at end of file diff --git a/src/integration_tests/camera_take_photo.cpp b/src/integration_tests/camera_take_photo.cpp index 74d9a82e63..cc59d8103e 100644 --- a/src/integration_tests/camera_take_photo.cpp +++ b/src/integration_tests/camera_take_photo.cpp @@ -25,7 +25,7 @@ TEST(CameraTest, TakePhotoSingle) info.index = index; info.is_success = true; - camera_server.respond_take_photo(CameraServer::TakePhotoFeedback::Ok, info); + camera_server.respond_take_photo(CameraServer::CameraFeedback::Ok, info); }); // Wait for system to connect via heartbeat. diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index e49200bf11..5d343cffcc 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -45,8 +45,8 @@ void CameraServer::unsubscribe_take_photo(TakePhotoHandle handle) _impl->unsubscribe_take_photo(handle); } -CameraServer::Result CameraServer::respond_take_photo( - TakePhotoFeedback take_photo_feedback, CaptureInfo capture_info) const +CameraServer::Result +CameraServer::respond_take_photo(CameraFeedback take_photo_feedback, CaptureInfo capture_info) const { return _impl->respond_take_photo(take_photo_feedback, capture_info); } @@ -62,6 +62,11 @@ void CameraServer::unsubscribe_start_video(StartVideoHandle handle) _impl->unsubscribe_start_video(handle); } +CameraServer::Result CameraServer::respond_start_video(CameraFeedback start_video_feedback) const +{ + return _impl->respond_start_video(start_video_feedback); +} + CameraServer::StopVideoHandle CameraServer::subscribe_stop_video(const StopVideoCallback& callback) { return _impl->subscribe_stop_video(callback); @@ -72,6 +77,11 @@ void CameraServer::unsubscribe_stop_video(StopVideoHandle handle) _impl->unsubscribe_stop_video(handle); } +CameraServer::Result CameraServer::respond_stop_video(CameraFeedback stop_video_feedback) const +{ + return _impl->respond_stop_video(stop_video_feedback); +} + CameraServer::StartVideoStreamingHandle CameraServer::subscribe_start_video_streaming(const StartVideoStreamingCallback& callback) { @@ -83,6 +93,12 @@ void CameraServer::unsubscribe_start_video_streaming(StartVideoStreamingHandle h _impl->unsubscribe_start_video_streaming(handle); } +CameraServer::Result +CameraServer::respond_start_video_streaming(CameraFeedback start_video_streaming_feedback) const +{ + return _impl->respond_start_video_streaming(start_video_streaming_feedback); +} + CameraServer::StopVideoStreamingHandle CameraServer::subscribe_stop_video_streaming(const StopVideoStreamingCallback& callback) { @@ -94,6 +110,12 @@ void CameraServer::unsubscribe_stop_video_streaming(StopVideoStreamingHandle han _impl->unsubscribe_stop_video_streaming(handle); } +CameraServer::Result +CameraServer::respond_stop_video_streaming(CameraFeedback stop_video_streaming_feedback) const +{ + return _impl->respond_stop_video_streaming(stop_video_streaming_feedback); +} + CameraServer::SetModeHandle CameraServer::subscribe_set_mode(const SetModeCallback& callback) { return _impl->subscribe_set_mode(callback); @@ -104,6 +126,11 @@ void CameraServer::unsubscribe_set_mode(SetModeHandle handle) _impl->unsubscribe_set_mode(handle); } +CameraServer::Result CameraServer::respond_set_mode(CameraFeedback set_mode_feedback) const +{ + return _impl->respond_set_mode(set_mode_feedback); +} + CameraServer::StorageInformationHandle CameraServer::subscribe_storage_information(const StorageInformationCallback& callback) { @@ -115,10 +142,10 @@ void CameraServer::unsubscribe_storage_information(StorageInformationHandle hand _impl->unsubscribe_storage_information(handle); } -CameraServer::Result -CameraServer::respond_storage_information(StorageInformation storage_information) const +CameraServer::Result CameraServer::respond_storage_information( + CameraFeedback storage_information_feedback, StorageInformation storage_information) const { - return _impl->respond_storage_information(storage_information); + return _impl->respond_storage_information(storage_information_feedback, storage_information); } CameraServer::CaptureStatusHandle @@ -132,9 +159,10 @@ void CameraServer::unsubscribe_capture_status(CaptureStatusHandle handle) _impl->unsubscribe_capture_status(handle); } -CameraServer::Result CameraServer::respond_capture_status(CaptureStatus capture_status) const +CameraServer::Result CameraServer::respond_capture_status( + CameraFeedback capture_status_feedback, CaptureStatus capture_status) const { - return _impl->respond_capture_status(capture_status); + return _impl->respond_capture_status(capture_status_feedback, capture_status); } CameraServer::FormatStorageHandle @@ -148,6 +176,12 @@ void CameraServer::unsubscribe_format_storage(FormatStorageHandle handle) _impl->unsubscribe_format_storage(handle); } +CameraServer::Result +CameraServer::respond_format_storage(CameraFeedback format_storage_feedback) const +{ + return _impl->respond_format_storage(format_storage_feedback); +} + CameraServer::ResetSettingsHandle CameraServer::subscribe_reset_settings(const ResetSettingsCallback& callback) { @@ -159,6 +193,12 @@ void CameraServer::unsubscribe_reset_settings(ResetSettingsHandle handle) _impl->unsubscribe_reset_settings(handle); } +CameraServer::Result +CameraServer::respond_reset_settings(CameraFeedback reset_settings_feedback) const +{ + return _impl->respond_reset_settings(reset_settings_feedback); +} + bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && @@ -413,17 +453,16 @@ std::ostream& operator<<(std::ostream& str, CameraServer::CaptureStatus const& c return str; } -std::ostream& -operator<<(std::ostream& str, CameraServer::TakePhotoFeedback const& take_photo_feedback) +std::ostream& operator<<(std::ostream& str, CameraServer::CameraFeedback const& camera_feedback) { - switch (take_photo_feedback) { - case CameraServer::TakePhotoFeedback::Unknown: + switch (camera_feedback) { + case CameraServer::CameraFeedback::Unknown: return str << "Unknown"; - case CameraServer::TakePhotoFeedback::Ok: + case CameraServer::CameraFeedback::Ok: return str << "Ok"; - case CameraServer::TakePhotoFeedback::Busy: + case CameraServer::CameraFeedback::Busy: return str << "Busy"; - case CameraServer::TakePhotoFeedback::Failed: + case CameraServer::CameraFeedback::Failed: return str << "Failed"; default: return str << "Unknown"; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index bfe49c9fe3..90a3ebf555 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -206,7 +206,7 @@ void CameraServerImpl::unsubscribe_take_photo(CameraServer::TakePhotoHandle hand } CameraServer::Result CameraServerImpl::respond_take_photo( - CameraServer::TakePhotoFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info) + CameraServer::CameraFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info) { // If capture_info.index == INT32_MIN, it means this was an interval // capture rather than a single image capture. @@ -225,9 +225,9 @@ CameraServer::Result CameraServerImpl::respond_take_photo( switch (take_photo_feedback) { default: // Fallthrough - case CameraServer::TakePhotoFeedback::Unknown: + case CameraServer::CameraFeedback::Unknown: return CameraServer::Result::Error; - case CameraServer::TakePhotoFeedback::Ok: { + case CameraServer::CameraFeedback::Ok: { // Check for error above auto command_ack = _server_component_impl->make_command_ack_message( _last_take_photo_command, MAV_RESULT_ACCEPTED); @@ -235,15 +235,16 @@ CameraServer::Result CameraServerImpl::respond_take_photo( // Only break and send the captured below. break; } - case CameraServer::TakePhotoFeedback::Busy: { + case CameraServer::CameraFeedback::Busy: { auto command_ack = _server_component_impl->make_command_ack_message( _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED); _server_component_impl->send_command_ack(command_ack); return CameraServer::Result::Success; } - case CameraServer::TakePhotoFeedback::Failed: { + + case CameraServer::CameraFeedback::Failed: { auto command_ack = _server_component_impl->make_command_ack_message( - _last_take_photo_command, MAV_RESULT_TEMPORARILY_REJECTED); + _last_take_photo_command, MAV_RESULT_FAILED); _server_component_impl->send_command_ack(command_ack); return CameraServer::Result::Success; } @@ -302,6 +303,36 @@ void CameraServerImpl::unsubscribe_start_video(CameraServer::StartVideoHandle ha _start_video_callbacks.unsubscribe(handle); } +CameraServer::Result +CameraServerImpl::respond_start_video(CameraServer::CameraFeedback start_video_feedback) +{ + switch (start_video_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::StopVideoHandle CameraServerImpl::subscribe_stop_video(const CameraServer::StopVideoCallback& callback) { @@ -313,6 +344,36 @@ void CameraServerImpl::unsubscribe_stop_video(CameraServer::StopVideoHandle hand return _stop_video_callbacks.unsubscribe(handle); } +CameraServer::Result +CameraServerImpl::respond_stop_video(CameraServer::CameraFeedback stop_video_feedback) +{ + switch (stop_video_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::StartVideoStreamingHandle CameraServerImpl::subscribe_start_video_streaming( const CameraServer::StartVideoStreamingCallback& callback) { @@ -325,6 +386,36 @@ void CameraServerImpl::unsubscribe_start_video_streaming( return _start_video_streaming_callbacks.unsubscribe(handle); } +CameraServer::Result CameraServerImpl::respond_start_video_streaming( + CameraServer::CameraFeedback start_video_streaming_feedback) +{ + switch (start_video_streaming_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_streaming_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_start_video_streaming_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::StopVideoStreamingHandle CameraServerImpl::subscribe_stop_video_streaming( const CameraServer::StopVideoStreamingCallback& callback) { @@ -337,6 +428,36 @@ void CameraServerImpl::unsubscribe_stop_video_streaming( return _stop_video_streaming_callbacks.unsubscribe(handle); } +CameraServer::Result CameraServerImpl::respond_stop_video_streaming( + CameraServer::CameraFeedback stop_video_streaming_feedback) +{ + switch (stop_video_streaming_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_streaming_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_streaming_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_stop_video_streaming_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::SetModeHandle CameraServerImpl::subscribe_set_mode(const CameraServer::SetModeCallback& callback) { @@ -348,6 +469,36 @@ void CameraServerImpl::unsubscribe_set_mode(CameraServer::SetModeHandle handle) _set_mode_callbacks.unsubscribe(handle); } +CameraServer::Result +CameraServerImpl::respond_set_mode(CameraServer::CameraFeedback set_mode_feedback) +{ + switch (set_mode_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_set_mode_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_set_mode_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_set_mode_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::StorageInformationHandle CameraServerImpl::subscribe_storage_information( const CameraServer::StorageInformationCallback& callback) { @@ -361,8 +512,35 @@ void CameraServerImpl::unsubscribe_storage_information( } CameraServer::Result CameraServerImpl::respond_storage_information( - CameraServer::StorageInformation storage_information) const + CameraServer::CameraFeedback storage_information_feedback, + CameraServer::StorageInformation storage_information) { + switch (storage_information_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_storage_information_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + // break and send storage information + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_storage_information_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_storage_information_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + const uint8_t storage_count = 1; const float total_capacity = storage_information.total_storage_mib; @@ -448,9 +626,36 @@ void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHan _capture_status_callbacks.unsubscribe(handle); } -CameraServer::Result -CameraServerImpl::respond_capture_status(CameraServer::CaptureStatus capture_status) const +CameraServer::Result CameraServerImpl::respond_capture_status( + CameraServer::CameraFeedback capture_status_feedback, + CameraServer::CaptureStatus capture_status) { + switch (capture_status_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_capture_status_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + // break and send capture status + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_capture_status_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_capture_status_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + uint8_t image_status{}; if (capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::CaptureInProgress || @@ -510,6 +715,36 @@ void CameraServerImpl::unsubscribe_format_storage(CameraServer::FormatStorageHan _format_storage_callbacks.unsubscribe(handle); } +CameraServer::Result +CameraServerImpl::respond_format_storage(CameraServer::CameraFeedback format_storage_feedback) +{ + switch (format_storage_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_format_storage_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_format_storage_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_format_storage_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + CameraServer::ResetSettingsHandle CameraServerImpl::subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback) { @@ -521,6 +756,36 @@ void CameraServerImpl::unsubscribe_reset_settings(CameraServer::ResetSettingsHan _reset_settings_callbacks.unsubscribe(handle); } +CameraServer::Result +CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback) +{ + switch (reset_settings_feedback) { + default: + // Fallthrough + case CameraServer::CameraFeedback::Unknown: + return CameraServer::Result::Error; + case CameraServer::CameraFeedback::Ok: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_reset_settings_command, MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + break; + } + case CameraServer::CameraFeedback::Busy: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_reset_settings_command, MAV_RESULT_TEMPORARILY_REJECTED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + case CameraServer::CameraFeedback::Failed: { + auto command_ack = _server_component_impl->make_command_ack_message( + _last_reset_settings_command, MAV_RESULT_FAILED); + _server_component_impl->send_command_ack(command_ack); + return CameraServer::Result::Success; + } + } + return CameraServer::Result::Success; +} + /** * Starts capturing images with the given interval. * @param [in] interval_s The interval between captures in seconds. @@ -702,6 +967,8 @@ std::optional CameraServerImpl::process_storage_informati // TODO may need support multi storage id _last_storage_id = storage_id; + + _last_storage_information_command = command; _storage_information_callbacks(storage_id); // unsupported @@ -762,10 +1029,10 @@ CameraServerImpl::process_storage_format(const MavlinkCommandReceiver::CommandLo command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_format_storage_command = command; _format_storage_callbacks(storage_id); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional CameraServerImpl::process_camera_capture_status_request( @@ -789,6 +1056,8 @@ std::optional CameraServerImpl::process_camera_capture_st _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); + _last_capture_status_command = command; + // may not need param for now ,just use zero _capture_status_callbacks(0); @@ -841,10 +1110,10 @@ CameraServerImpl::process_reset_camera_settings(const MavlinkCommandReceiver::Co command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_reset_settings_command = command; _reset_settings_callbacks(0); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional @@ -870,10 +1139,11 @@ CameraServerImpl::process_set_camera_mode(const MavlinkCommandReceiver::CommandL return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_DENIED); } + + _last_set_mode_command = command; _set_mode_callbacks(convert_camera_mode); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional @@ -957,9 +1227,6 @@ CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::Comm _last_take_photo_command = command; - // FIXME: why is this needed to prevent dropping messages? - // std::this_thread::sleep_for(std::chrono::milliseconds(100)); - _take_photo_callbacks(seq_number); return std::nullopt; @@ -1011,10 +1278,10 @@ CameraServerImpl::process_video_start_capture(const MavlinkCommandReceiver::Comm command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_start_video_command = command; _start_video_callbacks(stream_id); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional @@ -1028,10 +1295,10 @@ CameraServerImpl::process_video_stop_capture(const MavlinkCommandReceiver::Comma command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_stop_video_command = command; _stop_video_callbacks(stream_id); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional @@ -1045,10 +1312,10 @@ CameraServerImpl::process_video_start_streaming(const MavlinkCommandReceiver::Co command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_start_video_streaming_command = command; _start_video_streaming_callbacks(stream_id); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional @@ -1062,10 +1329,10 @@ CameraServerImpl::process_video_stop_streaming(const MavlinkCommandReceiver::Com command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); } + _last_stop_video_streaming_command = command; _stop_video_streaming_callbacks(stream_id); - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); + return std::nullopt; } std::optional CameraServerImpl::process_video_stream_information_request( diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 78e462ec55..474a3e4b01 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -21,46 +21,59 @@ class CameraServerImpl : public ServerPluginImplBase { subscribe_take_photo(const CameraServer::TakePhotoCallback& callback); void unsubscribe_take_photo(CameraServer::TakePhotoHandle handle); CameraServer::Result respond_take_photo( - CameraServer::TakePhotoFeedback take_photo_feedback, - CameraServer::CaptureInfo capture_info); + CameraServer::CameraFeedback take_photo_feedback, CameraServer::CaptureInfo capture_info); CameraServer::StartVideoHandle subscribe_start_video(const CameraServer::StartVideoCallback& callback); void unsubscribe_start_video(CameraServer::StartVideoHandle handle); + CameraServer::Result respond_start_video(CameraServer::CameraFeedback start_video_feedback); CameraServer::StopVideoHandle subscribe_stop_video(const CameraServer::StopVideoCallback& callback); void unsubscribe_stop_video(CameraServer::StopVideoHandle handle); + CameraServer::Result respond_stop_video(CameraServer::CameraFeedback stop_video_feedback); CameraServer::StartVideoStreamingHandle subscribe_start_video_streaming(const CameraServer::StartVideoStreamingCallback& callback); void unsubscribe_start_video_streaming(CameraServer::StartVideoStreamingHandle handle); + CameraServer::Result + respond_start_video_streaming(CameraServer::CameraFeedback start_video_streaming_feedback); CameraServer::StopVideoStreamingHandle subscribe_stop_video_streaming(const CameraServer::StopVideoStreamingCallback& callback); void unsubscribe_stop_video_streaming(CameraServer::StopVideoStreamingHandle handle); + CameraServer::Result + respond_stop_video_streaming(CameraServer::CameraFeedback stop_video_streaming_feedback); CameraServer::SetModeHandle subscribe_set_mode(const CameraServer::SetModeCallback& callback); void unsubscribe_set_mode(CameraServer::SetModeHandle handle); + CameraServer::Result respond_set_mode(CameraServer::CameraFeedback set_mode_feedback); CameraServer::StorageInformationHandle subscribe_storage_information(const CameraServer::StorageInformationCallback& callback); void unsubscribe_storage_information(CameraServer::StorageInformationHandle handle); - CameraServer::Result - respond_storage_information(CameraServer::StorageInformation storage_information) const; + CameraServer::Result respond_storage_information( + CameraServer::CameraFeedback storage_information_feedback, + CameraServer::StorageInformation storage_information); CameraServer::CaptureStatusHandle subscribe_capture_status(const CameraServer::CaptureStatusCallback& callback); void unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle); - CameraServer::Result respond_capture_status(CameraServer::CaptureStatus capture_status) const; + CameraServer::Result respond_capture_status( + CameraServer::CameraFeedback capture_status_feedback, + CameraServer::CaptureStatus capture_status); CameraServer::FormatStorageHandle subscribe_format_storage(const CameraServer::FormatStorageCallback& callback); void unsubscribe_format_storage(CameraServer::FormatStorageHandle handle); + CameraServer::Result + respond_format_storage(CameraServer::CameraFeedback format_storage_feedback); CameraServer::ResetSettingsHandle subscribe_reset_settings(const CameraServer::ResetSettingsCallback& callback); void unsubscribe_reset_settings(CameraServer::ResetSettingsHandle handle); + CameraServer::Result + respond_reset_settings(CameraServer::CameraFeedback reset_settings_feedback); private: enum StatusFlags { @@ -97,6 +110,16 @@ class CameraServerImpl : public ServerPluginImplBase { CallbackList _reset_settings_callbacks{}; MavlinkCommandReceiver::CommandLong _last_take_photo_command; + MavlinkCommandReceiver::CommandLong _last_start_video_command; + MavlinkCommandReceiver::CommandLong _last_stop_video_command; + MavlinkCommandReceiver::CommandLong _last_start_video_streaming_command; + MavlinkCommandReceiver::CommandLong _last_stop_video_streaming_command; + MavlinkCommandReceiver::CommandLong _last_set_mode_command; + MavlinkCommandReceiver::CommandLong _last_storage_information_command; + MavlinkCommandReceiver::CommandLong _last_capture_status_command; + MavlinkCommandReceiver::CommandLong _last_format_storage_command; + MavlinkCommandReceiver::CommandLong _last_reset_settings_command; + uint8_t _last_storage_id; bool parse_version_string(const std::string& version_str); diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index a9caf7bf71..ef33caef52 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -46,9 +46,9 @@ class CameraServer : public ServerPluginBase { ~CameraServer() override; /** - * @brief Possible results when taking a photo. + * @brief Possible feedback results for camera respond command. */ - enum class TakePhotoFeedback { + enum class CameraFeedback { Unknown, /**< @brief Unknown. */ Ok, /**< @brief Ok. */ Busy, /**< @brief Busy. */ @@ -56,12 +56,12 @@ class CameraServer : public ServerPluginBase { }; /** - * @brief Stream operator to print information about a `CameraServer::TakePhotoFeedback`. + * @brief Stream operator to print information about a `CameraServer::CameraFeedback`. * * @return A reference to the stream. */ friend std::ostream& - operator<<(std::ostream& str, CameraServer::TakePhotoFeedback const& take_photo_feedback); + operator<<(std::ostream& str, CameraServer::CameraFeedback const& camera_feedback); /** * @brief Camera mode type. @@ -408,8 +408,7 @@ class CameraServer : public ServerPluginBase { * * @return Result of request. */ - Result - respond_take_photo(TakePhotoFeedback take_photo_feedback, CaptureInfo capture_info) const; + Result respond_take_photo(CameraFeedback take_photo_feedback, CaptureInfo capture_info) const; /** * @brief Callback type for subscribe_start_video. @@ -423,7 +422,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to start video requests. Each request received should response to using - * StartVideoResponse + * RespondStartVideo */ StartVideoHandle subscribe_start_video(const StartVideoCallback& callback); @@ -432,6 +431,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_start_video(StartVideoHandle handle); + /** + * @brief Respond to start video request from SubscribeStartVideo. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_start_video(CameraFeedback start_video_feedback) const; + /** * @brief Callback type for subscribe_stop_video. */ @@ -444,7 +452,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to stop video requests. Each request received should response to using - * StopVideoResponse + * RespondStopVideo */ StopVideoHandle subscribe_stop_video(const StopVideoCallback& callback); @@ -453,6 +461,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_stop_video(StopVideoHandle handle); + /** + * @brief Respond to stop video request from SubscribeStopVideo. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_stop_video(CameraFeedback stop_video_feedback) const; + /** * @brief Callback type for subscribe_start_video_streaming. */ @@ -465,7 +482,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to start video streaming requests. Each request received should response to - * using StartVideoStreamingResponse + * using RespondStartVideoStreaming */ StartVideoStreamingHandle subscribe_start_video_streaming(const StartVideoStreamingCallback& callback); @@ -475,6 +492,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_start_video_streaming(StartVideoStreamingHandle handle); + /** + * @brief Respond to start video streaming from SubscribeStartVideoStreaming. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_start_video_streaming(CameraFeedback start_video_streaming_feedback) const; + /** * @brief Callback type for subscribe_stop_video_streaming. */ @@ -487,7 +513,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to stop video streaming requests. Each request received should response to - * using StopVideoStreamingResponse + * using RespondStopVideoStreaming */ StopVideoStreamingHandle subscribe_stop_video_streaming(const StopVideoStreamingCallback& callback); @@ -497,6 +523,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_stop_video_streaming(StopVideoStreamingHandle handle); + /** + * @brief Respond to stop video streaming from SubscribeStopVideoStreaming. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_stop_video_streaming(CameraFeedback stop_video_streaming_feedback) const; + /** * @brief Callback type for subscribe_set_mode. */ @@ -509,7 +544,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to set camera mode requests. Each request received should response to using - * SetCameraModeResponse + * RespondSetMode */ SetModeHandle subscribe_set_mode(const SetModeCallback& callback); @@ -518,6 +553,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_set_mode(SetModeHandle handle); + /** + * @brief Respond to set camera mode from SubscribeSetMode. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_set_mode(CameraFeedback set_mode_feedback) const; + /** * @brief Callback type for subscribe_storage_information. */ @@ -530,7 +574,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to camera storage information requests. Each request received should - * response to using StorageInformationResponse + * response to using RespondStorageInformation */ StorageInformationHandle subscribe_storage_information(const StorageInformationCallback& callback); @@ -547,7 +591,8 @@ class CameraServer : public ServerPluginBase { * * @return Result of request. */ - Result respond_storage_information(StorageInformation storage_information) const; + Result respond_storage_information( + CameraFeedback storage_information_feedback, StorageInformation storage_information) const; /** * @brief Callback type for subscribe_capture_status. @@ -561,7 +606,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to camera capture status requests. Each request received should response to - * using CaptureStatusResponse + * using RespondCaptureStatus */ CaptureStatusHandle subscribe_capture_status(const CaptureStatusCallback& callback); @@ -577,7 +622,8 @@ class CameraServer : public ServerPluginBase { * * @return Result of request. */ - Result respond_capture_status(CaptureStatus capture_status) const; + Result respond_capture_status( + CameraFeedback capture_status_feedback, CaptureStatus capture_status) const; /** * @brief Callback type for subscribe_format_storage. @@ -591,7 +637,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to format storage requests. Each request received should response to using - * FormatStorageResponse + * RespondFormatStorage */ FormatStorageHandle subscribe_format_storage(const FormatStorageCallback& callback); @@ -600,6 +646,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_format_storage(FormatStorageHandle handle); + /** + * @brief Respond to format storage from SubscribeFormatStorage. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_format_storage(CameraFeedback format_storage_feedback) const; + /** * @brief Callback type for subscribe_reset_settings. */ @@ -612,7 +667,7 @@ class CameraServer : public ServerPluginBase { /** * @brief Subscribe to reset settings requests. Each request received should response to using - * ResetSettingsResponse + * RespondResetSettings */ ResetSettingsHandle subscribe_reset_settings(const ResetSettingsCallback& callback); @@ -621,6 +676,15 @@ class CameraServer : public ServerPluginBase { */ void unsubscribe_reset_settings(ResetSettingsHandle handle); + /** + * @brief Respond to reset settings from SubscribeResetSettings. + * + * This function is blocking. + * + * @return Result of request. + */ + Result respond_reset_settings(CameraFeedback reset_settings_feedback) const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index cfae56f5e7..adc2c9615e 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -29,16 +29,23 @@ static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideo", + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideo", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideo", + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideo", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStartVideoStreaming", + "/mavsdk.rpc.camera_server.CameraServerService/RespondStartVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStopVideoStreaming", + "/mavsdk.rpc.camera_server.CameraServerService/RespondStopVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeSetMode", + "/mavsdk.rpc.camera_server.CameraServerService/RespondSetMode", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeStorageInformation", "/mavsdk.rpc.camera_server.CameraServerService/RespondStorageInformation", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeCaptureStatus", "/mavsdk.rpc.camera_server.CameraServerService/RespondCaptureStatus", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeFormatStorage", + "/mavsdk.rpc.camera_server.CameraServerService/RespondFormatStorage", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeResetSettings", + "/mavsdk.rpc.camera_server.CameraServerService/RespondResetSettings", }; std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -53,16 +60,23 @@ CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface> , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStorageInformation_(CameraServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeFormatStorage_(CameraServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStartVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStopVideo_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStartVideoStreaming_(CameraServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStopVideoStreaming_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondSetMode_(CameraServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStorageInformation_(CameraServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeFormatStorage_(CameraServerService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondFormatStorage_(CameraServerService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondResetSettings_(CameraServerService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -166,6 +180,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* Ca return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideo_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondStartVideo_, context, request, response); +} + +void CameraServerService::Stub::async::RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStartVideo_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStartVideo_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* CameraServerService::Stub::PrepareAsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondStartVideoResponse, ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondStartVideo_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* CameraServerService::Stub::AsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondStartVideoRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* CameraServerService::Stub::SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), rpcmethod_SubscribeStopVideo_, context, request); } @@ -182,6 +219,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* Cam return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideo_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondStopVideo_, context, request, response); +} + +void CameraServerService::Stub::async::RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStopVideo_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStopVideo_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* CameraServerService::Stub::PrepareAsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondStopVideoResponse, ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondStopVideo_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* CameraServerService::Stub::AsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondStopVideoRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* CameraServerService::Stub::SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(channel_.get(), rpcmethod_SubscribeStartVideoStreaming_, context, request); } @@ -198,6 +258,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResp return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStartVideoStreaming_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondStartVideoStreaming_, context, request, response); +} + +void CameraServerService::Stub::async::RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStartVideoStreaming_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStartVideoStreaming_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondStartVideoStreaming_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* CameraServerService::Stub::AsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondStartVideoStreamingRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* CameraServerService::Stub::SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), rpcmethod_SubscribeStopVideoStreaming_, context, request); } @@ -214,6 +297,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingRespo return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStopVideoStreaming_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondStopVideoStreaming_, context, request, response); +} + +void CameraServerService::Stub::async::RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStopVideoStreaming_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondStopVideoStreaming_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondStopVideoStreaming_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* CameraServerService::Stub::AsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondStopVideoStreamingRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>* CameraServerService::Stub::SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), rpcmethod_SubscribeSetMode_, context, request); } @@ -230,6 +336,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* Camer return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::SetModeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeSetMode_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondSetMode_, context, request, response); +} + +void CameraServerService::Stub::async::RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondSetMode_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondSetMode_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* CameraServerService::Stub::PrepareAsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondSetModeResponse, ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondSetMode_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* CameraServerService::Stub::AsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondSetModeRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* CameraServerService::Stub::SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::StorageInformationResponse>::Create(channel_.get(), rpcmethod_SubscribeStorageInformation_, context, request); } @@ -324,6 +453,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::FormatStorageResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeFormatStorage_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondFormatStorage_, context, request, response); +} + +void CameraServerService::Stub::async::RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondFormatStorage_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondFormatStorage_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* CameraServerService::Stub::PrepareAsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse, ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondFormatStorage_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* CameraServerService::Stub::AsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondFormatStorageRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* CameraServerService::Stub::SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(channel_.get(), rpcmethod_SubscribeResetSettings_, context, request); } @@ -340,6 +492,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera_server::ResetSettingsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeResetSettings_, context, request, false, nullptr); } +::grpc::Status CameraServerService::Stub::RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RespondResetSettings_, context, request, response); +} + +void CameraServerService::Stub::async::RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondResetSettings_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_RespondResetSettings_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* CameraServerService::Stub::PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse, ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_RespondResetSettings_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* CameraServerService::Stub::AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncRespondResetSettingsRaw(context, request, cq); + result->StartCall(); + return result; +} + CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[0], @@ -393,6 +568,16 @@ CameraServerService::Service::Service() { }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[5], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* req, + ::mavsdk::rpc::camera_server::RespondStartVideoResponse* resp) { + return service->RespondStartVideo(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[6], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [](CameraServerService::Service* service, @@ -402,7 +587,17 @@ CameraServerService::Service::Service() { return service->SubscribeStopVideo(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[6], + CameraServerService_method_names[7], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* req, + ::mavsdk::rpc::camera_server::RespondStopVideoResponse* resp) { + return service->RespondStopVideo(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[8], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [](CameraServerService::Service* service, @@ -412,7 +607,17 @@ CameraServerService::Service::Service() { return service->SubscribeStartVideoStreaming(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[7], + CameraServerService_method_names[9], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* req, + ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* resp) { + return service->RespondStartVideoStreaming(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [](CameraServerService::Service* service, @@ -422,7 +627,17 @@ CameraServerService::Service::Service() { return service->SubscribeStopVideoStreaming(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[8], + CameraServerService_method_names[11], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* req, + ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* resp) { + return service->RespondStopVideoStreaming(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[12], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [](CameraServerService::Service* service, @@ -432,7 +647,17 @@ CameraServerService::Service::Service() { return service->SubscribeSetMode(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[9], + CameraServerService_method_names[13], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondSetModeRequest* req, + ::mavsdk::rpc::camera_server::RespondSetModeResponse* resp) { + return service->RespondSetMode(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [](CameraServerService::Service* service, @@ -442,7 +667,7 @@ CameraServerService::Service::Service() { return service->SubscribeStorageInformation(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[10], + CameraServerService_method_names[15], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -452,7 +677,7 @@ CameraServerService::Service::Service() { return service->RespondStorageInformation(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[11], + CameraServerService_method_names[16], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [](CameraServerService::Service* service, @@ -462,7 +687,7 @@ CameraServerService::Service::Service() { return service->SubscribeCaptureStatus(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[12], + CameraServerService_method_names[17], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -472,7 +697,7 @@ CameraServerService::Service::Service() { return service->RespondCaptureStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[13], + CameraServerService_method_names[18], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [](CameraServerService::Service* service, @@ -482,7 +707,17 @@ CameraServerService::Service::Service() { return service->SubscribeFormatStorage(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[14], + CameraServerService_method_names[19], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* req, + ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* resp) { + return service->RespondFormatStorage(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[20], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [](CameraServerService::Service* service, @@ -491,6 +726,16 @@ CameraServerService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer) { return service->SubscribeResetSettings(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[21], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* req, + ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* resp) { + return service->RespondResetSettings(ctx, req, resp); + }, this))); } CameraServerService::Service::~Service() { @@ -531,6 +776,13 @@ ::grpc::Status CameraServerService::Service::SubscribeStartVideo(::grpc::ServerC return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer) { (void) context; (void) request; @@ -538,6 +790,13 @@ ::grpc::Status CameraServerService::Service::SubscribeStopVideo(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer) { (void) context; (void) request; @@ -545,6 +804,13 @@ ::grpc::Status CameraServerService::Service::SubscribeStartVideoStreaming(::grpc return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer) { (void) context; (void) request; @@ -552,6 +818,13 @@ ::grpc::Status CameraServerService::Service::SubscribeStopVideoStreaming(::grpc: return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer) { (void) context; (void) request; @@ -559,6 +832,13 @@ ::grpc::Status CameraServerService::Service::SubscribeSetMode(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer) { (void) context; (void) request; @@ -594,6 +874,13 @@ ::grpc::Status CameraServerService::Service::SubscribeFormatStorage(::grpc::Serv return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondFormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SubscribeResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer) { (void) context; (void) request; @@ -601,6 +888,13 @@ ::grpc::Status CameraServerService::Service::SubscribeResetSettings(::grpc::Serv return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::RespondResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* 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/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index 20bcff1828..d547c610e6 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -72,7 +72,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } - // Subscribe to start video requests. Each request received should response to using StartVideoResponse + // Subscribe to start video requests. Each request received should response to using RespondStartVideo std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); } @@ -82,7 +82,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); } - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + // Respond to start video request from SubscribeStartVideo. + virtual ::grpc::Status RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>> AsyncRespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>>(AsyncRespondStartVideoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>> PrepareAsyncRespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>>(PrepareAsyncRespondStartVideoRaw(context, request, cq)); + } + // Subscribe to stop video requests. Each request received should response to using RespondStopVideo std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); } @@ -92,7 +100,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); } - // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + // Respond to stop video request from SubscribeStopVideo. + virtual ::grpc::Status RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>> AsyncRespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>>(AsyncRespondStopVideoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>> PrepareAsyncRespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>>(PrepareAsyncRespondStopVideoRaw(context, request, cq)); + } + // Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(SubscribeStartVideoStreamingRaw(context, request)); } @@ -102,7 +118,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> PrepareAsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(PrepareAsyncSubscribeStartVideoStreamingRaw(context, request, cq)); } - // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + // Respond to start video streaming from SubscribeStartVideoStreaming. + virtual ::grpc::Status RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>> AsyncRespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>>(AsyncRespondStartVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>> PrepareAsyncRespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>>(PrepareAsyncRespondStartVideoStreamingRaw(context, request, cq)); + } + // Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(SubscribeStopVideoStreamingRaw(context, request)); } @@ -112,7 +136,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); } - // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + // Respond to stop video streaming from SubscribeStopVideoStreaming. + virtual ::grpc::Status RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>> AsyncRespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>>(AsyncRespondStopVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>> PrepareAsyncRespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>>(PrepareAsyncRespondStopVideoStreamingRaw(context, request, cq)); + } + // Subscribe to set camera mode requests. Each request received should response to using RespondSetMode std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(SubscribeSetModeRaw(context, request)); } @@ -122,7 +154,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); } - // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + // Respond to set camera mode from SubscribeSetMode. + virtual ::grpc::Status RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>> AsyncRespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>>(AsyncRespondSetModeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>> PrepareAsyncRespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>>(PrepareAsyncRespondSetModeRaw(context, request, cq)); + } + // Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>> SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(SubscribeStorageInformationRaw(context, request)); } @@ -140,7 +180,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>> PrepareAsyncRespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>>(PrepareAsyncRespondStorageInformationRaw(context, request, cq)); } - // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + // Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>> SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::CaptureStatusResponse>>(SubscribeCaptureStatusRaw(context, request)); } @@ -158,7 +198,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>> PrepareAsyncRespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>>(PrepareAsyncRespondCaptureStatusRaw(context, request, cq)); } - // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + // Subscribe to format storage requests. Each request received should response to using RespondFormatStorage std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>> SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(SubscribeFormatStorageRaw(context, request)); } @@ -168,7 +208,15 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>> PrepareAsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(PrepareAsyncSubscribeFormatStorageRaw(context, request, cq)); } - // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + // Respond to format storage from SubscribeFormatStorage. + virtual ::grpc::Status RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>> AsyncRespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>>(AsyncRespondFormatStorageRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>> PrepareAsyncRespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>>(PrepareAsyncRespondFormatStorageRaw(context, request, cq)); + } + // Subscribe to reset settings requests. Each request received should response to using RespondResetSettings std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(SubscribeResetSettingsRaw(context, request)); } @@ -178,6 +226,14 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> PrepareAsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(PrepareAsyncSubscribeResetSettingsRaw(context, request, cq)); } + // Respond to reset settings from SubscribeResetSettings. + virtual ::grpc::Status RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> AsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(AsyncRespondResetSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> PrepareAsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(PrepareAsyncRespondResetSettingsRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -192,30 +248,51 @@ class CameraServerService final { // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to start video requests. Each request received should response to using StartVideoResponse + // Subscribe to start video requests. Each request received should response to using RespondStartVideo virtual void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) = 0; - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + // Respond to start video request from SubscribeStartVideo. + virtual void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, std::function) = 0; + virtual void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to stop video requests. Each request received should response to using RespondStopVideo virtual void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) = 0; - // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + // Respond to stop video request from SubscribeStopVideo. + virtual void RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, std::function) = 0; + virtual void RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming virtual void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) = 0; - // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + // Respond to start video streaming from SubscribeStartVideoStreaming. + virtual void RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, std::function) = 0; + virtual void RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming virtual void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) = 0; - // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + // Respond to stop video streaming from SubscribeStopVideoStreaming. + virtual void RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, std::function) = 0; + virtual void RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to set camera mode requests. Each request received should response to using RespondSetMode virtual void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) = 0; - // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + // Respond to set camera mode from SubscribeSetMode. + virtual void RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, std::function) = 0; + virtual void RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation virtual void SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* reactor) = 0; // Respond to camera storage information from SubscribeStorageInformation. virtual void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, std::function) = 0; virtual void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + // Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus virtual void SubscribeCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* reactor) = 0; // Respond to camera capture status from SubscribeCaptureStatus. virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) = 0; virtual void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + // Subscribe to format storage requests. Each request received should response to using RespondFormatStorage virtual void SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* reactor) = 0; - // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + // Respond to format storage from SubscribeFormatStorage. + virtual void RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, std::function) = 0; + virtual void RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to reset settings requests. Each request received should response to using RespondResetSettings virtual void SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) = 0; + // Respond to reset settings from SubscribeResetSettings. + virtual void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, std::function) = 0; + virtual void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -233,18 +310,28 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* AsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* PrepareAsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* AsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* PrepareAsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* AsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* PrepareAsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* AsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* PrepareAsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* AsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* PrepareAsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* AsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* PrepareAsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* AsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StorageInformationResponse>* PrepareAsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -258,9 +345,13 @@ class CameraServerService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* SubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* AsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::FormatStorageResponse>* PrepareAsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* AsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* PrepareAsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* AsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -304,6 +395,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); } + ::grpc::Status RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>> AsyncRespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>>(AsyncRespondStartVideoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>> PrepareAsyncRespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>>(PrepareAsyncRespondStartVideoRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(SubscribeStopVideoRaw(context, request)); } @@ -313,6 +411,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>> PrepareAsyncSubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>>(PrepareAsyncSubscribeStopVideoRaw(context, request, cq)); } + ::grpc::Status RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>> AsyncRespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>>(AsyncRespondStopVideoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>> PrepareAsyncRespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>>(PrepareAsyncRespondStopVideoRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(SubscribeStartVideoStreamingRaw(context, request)); } @@ -322,6 +427,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>> PrepareAsyncSubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>>(PrepareAsyncSubscribeStartVideoStreamingRaw(context, request, cq)); } + ::grpc::Status RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>> AsyncRespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>>(AsyncRespondStartVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>> PrepareAsyncRespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>>(PrepareAsyncRespondStartVideoStreamingRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(SubscribeStopVideoStreamingRaw(context, request)); } @@ -331,6 +443,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>> PrepareAsyncSubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>>(PrepareAsyncSubscribeStopVideoStreamingRaw(context, request, cq)); } + ::grpc::Status RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>> AsyncRespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>>(AsyncRespondStopVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>> PrepareAsyncRespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>>(PrepareAsyncRespondStopVideoStreamingRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>> SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(SubscribeSetModeRaw(context, request)); } @@ -340,6 +459,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>> PrepareAsyncSubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>>(PrepareAsyncSubscribeSetModeRaw(context, request, cq)); } + ::grpc::Status RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>> AsyncRespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>>(AsyncRespondSetModeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>> PrepareAsyncRespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>>(PrepareAsyncRespondSetModeRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>> SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>>(SubscribeStorageInformationRaw(context, request)); } @@ -381,6 +507,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>> PrepareAsyncSubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>>(PrepareAsyncSubscribeFormatStorageRaw(context, request, cq)); } + ::grpc::Status RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>> AsyncRespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>>(AsyncRespondFormatStorageRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>> PrepareAsyncRespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>>(PrepareAsyncRespondFormatStorageRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(SubscribeResetSettingsRaw(context, request)); } @@ -390,6 +523,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>> PrepareAsyncSubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>>(PrepareAsyncSubscribeResetSettingsRaw(context, request, cq)); } + ::grpc::Status RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> AsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(AsyncRespondResetSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>> PrepareAsyncRespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>>(PrepareAsyncRespondResetSettingsRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -401,10 +541,20 @@ class CameraServerService final { void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) override; void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) override; + void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, std::function) override; + void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoResponse>* reactor) override; + void RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, std::function) override; + void RespondStopVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* reactor) override; + void RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, std::function) override; + void RespondStartVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* reactor) override; + void RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, std::function) override; + void RespondStopVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::SetModeResponse>* reactor) override; + void RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, std::function) override; + void RespondSetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StorageInformationResponse>* reactor) override; void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, std::function) override; void RespondStorageInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) override; @@ -412,7 +562,11 @@ class CameraServerService final { void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, std::function) override; void RespondCaptureStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::FormatStorageResponse>* reactor) override; + void RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, std::function) override; + void RespondFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* reactor) override; + void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, std::function) override; + void RespondResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -436,18 +590,28 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* SubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* AsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoResponse>* PrepareAsyncSubscribeStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* AsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* PrepareAsyncRespondStartVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* SubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* AsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoResponse>* PrepareAsyncSubscribeStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* AsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* PrepareAsyncRespondStopVideoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* SubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* AsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* PrepareAsyncSubscribeStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* AsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* PrepareAsyncRespondStartVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* SubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* AsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* PrepareAsyncSubscribeStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* AsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* PrepareAsyncRespondStopVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::SetModeResponse>* SubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* AsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::SetModeResponse>* PrepareAsyncSubscribeSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* AsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* PrepareAsyncRespondSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* SubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* AsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::StorageInformationResponse>* PrepareAsyncSubscribeStorageInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest& request, ::grpc::CompletionQueue* cq) override; @@ -461,24 +625,35 @@ class CameraServerService final { ::grpc::ClientReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* SubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* AsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::FormatStorageResponse>* PrepareAsyncSubscribeFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* AsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* PrepareAsyncRespondFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* AsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* PrepareAsyncSubscribeResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideo_; + const ::grpc::internal::RpcMethod rpcmethod_RespondStartVideo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideo_; + const ::grpc::internal::RpcMethod rpcmethod_RespondStopVideo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStartVideoStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_RespondStartVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStopVideoStreaming_; + const ::grpc::internal::RpcMethod rpcmethod_RespondStopVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeSetMode_; + const ::grpc::internal::RpcMethod rpcmethod_RespondSetMode_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStorageInformation_; const ::grpc::internal::RpcMethod rpcmethod_RespondStorageInformation_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCaptureStatus_; const ::grpc::internal::RpcMethod rpcmethod_RespondCaptureStatus_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeFormatStorage_; + const ::grpc::internal::RpcMethod rpcmethod_RespondFormatStorage_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeResetSettings_; + const ::grpc::internal::RpcMethod rpcmethod_RespondResetSettings_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -494,28 +669,42 @@ class CameraServerService final { virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); - // Subscribe to start video requests. Each request received should response to using StartVideoResponse + // Subscribe to start video requests. Each request received should response to using RespondStartVideo virtual ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer); - // Subscribe to stop video requests. Each request received should response to using StopVideoResponse + // Respond to start video request from SubscribeStartVideo. + virtual ::grpc::Status RespondStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response); + // Subscribe to stop video requests. Each request received should response to using RespondStopVideo virtual ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer); - // Subscribe to start video streaming requests. Each request received should response to using StartVideoStreamingResponse + // Respond to stop video request from SubscribeStopVideo. + virtual ::grpc::Status RespondStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response); + // Subscribe to start video streaming requests. Each request received should response to using RespondStartVideoStreaming virtual ::grpc::Status SubscribeStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer); - // Subscribe to stop video streaming requests. Each request received should response to using StopVideoStreamingResponse + // Respond to start video streaming from SubscribeStartVideoStreaming. + virtual ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response); + // Subscribe to stop video streaming requests. Each request received should response to using RespondStopVideoStreaming virtual ::grpc::Status SubscribeStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer); - // Subscribe to set camera mode requests. Each request received should response to using SetCameraModeResponse + // Respond to stop video streaming from SubscribeStopVideoStreaming. + virtual ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response); + // Subscribe to set camera mode requests. Each request received should response to using RespondSetMode virtual ::grpc::Status SubscribeSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer); - // Subscribe to camera storage information requests. Each request received should response to using StorageInformationResponse + // Respond to set camera mode from SubscribeSetMode. + virtual ::grpc::Status RespondSetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response); + // Subscribe to camera storage information requests. Each request received should response to using RespondStorageInformation virtual ::grpc::Status SubscribeStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer); // Respond to camera storage information from SubscribeStorageInformation. virtual ::grpc::Status RespondStorageInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response); - // Subscribe to camera capture status requests. Each request received should response to using CaptureStatusResponse + // Subscribe to camera capture status requests. Each request received should response to using RespondCaptureStatus virtual ::grpc::Status SubscribeCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer); // Respond to camera capture status from SubscribeCaptureStatus. virtual ::grpc::Status RespondCaptureStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response); - // Subscribe to format storage requests. Each request received should response to using FormatStorageResponse + // Subscribe to format storage requests. Each request received should response to using RespondFormatStorage virtual ::grpc::Status SubscribeFormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer); - // Subscribe to reset settings requests. Each request received should response to using ResetSettingsResponse + // Respond to format storage from SubscribeFormatStorage. + virtual ::grpc::Status RespondFormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response); + // Subscribe to reset settings requests. Each request received should response to using RespondResetSettings virtual ::grpc::Status SubscribeResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer); + // Respond to reset settings from SubscribeResetSettings. + virtual ::grpc::Status RespondResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response); }; template class WithAsyncMethod_SetInformation : public BaseClass { @@ -618,12 +807,32 @@ class CameraServerService final { } }; template + class WithAsyncMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodAsync(5); + } + ~WithAsyncMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_SubscribeStopVideo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodAsync(5); + ::grpc::Service::MarkMethodAsync(6); } ~WithAsyncMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -634,7 +843,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodAsync(7); + } + ~WithAsyncMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -643,7 +872,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -654,7 +883,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodAsync(9); + } + ~WithAsyncMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -663,7 +912,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(10); } ~WithAsyncMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -674,7 +923,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodAsync(11); + } + ~WithAsyncMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -683,7 +952,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(12); } ~WithAsyncMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -694,7 +963,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondSetMode() { + ::grpc::Service::MarkMethodAsync(13); + } + ~WithAsyncMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(13, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -703,7 +992,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodAsync(9); + ::grpc::Service::MarkMethodAsync(14); } ~WithAsyncMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -714,7 +1003,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -723,7 +1012,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodAsync(10); + ::grpc::Service::MarkMethodAsync(15); } ~WithAsyncMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -734,7 +1023,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(15, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -743,7 +1032,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodAsync(11); + ::grpc::Service::MarkMethodAsync(16); } ~WithAsyncMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -754,7 +1043,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -763,7 +1052,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodAsync(12); + ::grpc::Service::MarkMethodAsync(17); } ~WithAsyncMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -774,7 +1063,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(12, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(17, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -783,7 +1072,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodAsync(13); + ::grpc::Service::MarkMethodAsync(18); } ~WithAsyncMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -794,7 +1083,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodAsync(19); + } + ~WithAsyncMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(19, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -803,7 +1112,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodAsync(14); + ::grpc::Service::MarkMethodAsync(20); } ~WithAsyncMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -814,10 +1123,30 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_RespondResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodAsync(21); + } + ~WithAsyncMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > AsyncService; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -944,12 +1273,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodCallback(5, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) { return this->RespondStartVideo(context, request, response); }));} + void SetMessageAllocatorFor_RespondStartVideo( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStartVideo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeStopVideo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodCallback(5, + ::grpc::Service::MarkMethodCallback(6, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request) { return this->SubscribeStopVideo(context, request); })); @@ -966,12 +1322,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodCallback(7, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) { return this->RespondStopVideo(context, request, response); }));} + void SetMessageAllocatorFor_RespondStopVideo( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStopVideo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeStartVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request) { return this->SubscribeStartVideoStreaming(context, request); })); @@ -988,12 +1371,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodCallback(9, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) { return this->RespondStartVideoStreaming(context, request, response); }));} + void SetMessageAllocatorFor_RespondStartVideoStreaming( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(9); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStartVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeStopVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodCallback(7, + ::grpc::Service::MarkMethodCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request) { return this->SubscribeStopVideoStreaming(context, request); })); @@ -1010,12 +1420,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodCallback(11, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) { return this->RespondStopVideoStreaming(context, request, response); }));} + void SetMessageAllocatorFor_RespondStopVideoStreaming( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(11); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStopVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeSetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodCallback(8, + ::grpc::Service::MarkMethodCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request) { return this->SubscribeSetMode(context, request); })); @@ -1032,12 +1469,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondSetMode() { + ::grpc::Service::MarkMethodCallback(13, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) { return this->RespondSetMode(context, request, response); }));} + void SetMessageAllocatorFor_RespondSetMode( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(13); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondSetMode( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeStorageInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodCallback(9, + ::grpc::Service::MarkMethodCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request) { return this->SubscribeStorageInformation(context, request); })); @@ -1059,13 +1523,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodCallback(10, + ::grpc::Service::MarkMethodCallback(15, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) { return this->RespondStorageInformation(context, request, response); }));} void SetMessageAllocatorFor_RespondStorageInformation( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(10); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(15); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1086,7 +1550,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodCallback(11, + ::grpc::Service::MarkMethodCallback(16, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request) { return this->SubscribeCaptureStatus(context, request); })); @@ -1108,13 +1572,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodCallback(12, + ::grpc::Service::MarkMethodCallback(17, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) { return this->RespondCaptureStatus(context, request, response); }));} void SetMessageAllocatorFor_RespondCaptureStatus( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(12); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(17); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1135,7 +1599,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodCallback(13, + ::grpc::Service::MarkMethodCallback(18, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request) { return this->SubscribeFormatStorage(context, request); })); @@ -1152,12 +1616,39 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodCallback(19, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) { return this->RespondFormatStorage(context, request, response); }));} + void SetMessageAllocatorFor_RespondFormatStorage( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(19); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondFormatStorage( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodCallback(14, + ::grpc::Service::MarkMethodCallback(20, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request) { return this->SubscribeResetSettings(context, request); })); @@ -1173,17 +1664,44 @@ class CameraServerService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* SubscribeResetSettings( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > CallbackService; - typedef CallbackService ExperimentalCallbackService; template - class WithGenericMethod_SetInformation : public BaseClass { + class WithCallbackMethod_RespondResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SetInformation() { - ::grpc::Service::MarkMethodGeneric(0); + WithCallbackMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response) { return this->RespondResetSettings(context, request, response); }));} + void SetMessageAllocatorFor_RespondResetSettings( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(21); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_SetInformation() override { + ~WithCallbackMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > CallbackService; + typedef CallbackService ExperimentalCallbackService; + template + class WithGenericMethod_SetInformation : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetInformation() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SetInformation() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method @@ -1261,12 +1779,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodGeneric(5); + } + ~WithGenericMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeStopVideo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodGeneric(5); + ::grpc::Service::MarkMethodGeneric(6); } ~WithGenericMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1278,12 +1813,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodGeneric(7); + } + ~WithGenericMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeStartVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1295,12 +1847,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodGeneric(9); + } + ~WithGenericMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeStopVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(10); } ~WithGenericMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1312,12 +1881,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodGeneric(11); + } + ~WithGenericMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeSetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(12); } ~WithGenericMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -1329,12 +1915,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondSetMode() { + ::grpc::Service::MarkMethodGeneric(13); + } + ~WithGenericMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeStorageInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodGeneric(9); + ::grpc::Service::MarkMethodGeneric(14); } ~WithGenericMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1351,7 +1954,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodGeneric(10); + ::grpc::Service::MarkMethodGeneric(15); } ~WithGenericMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1368,7 +1971,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodGeneric(11); + ::grpc::Service::MarkMethodGeneric(16); } ~WithGenericMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1385,7 +1988,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodGeneric(12); + ::grpc::Service::MarkMethodGeneric(17); } ~WithGenericMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1402,7 +2005,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodGeneric(13); + ::grpc::Service::MarkMethodGeneric(18); } ~WithGenericMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -1414,12 +2017,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodGeneric(19); + } + ~WithGenericMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodGeneric(14); + ::grpc::Service::MarkMethodGeneric(20); } ~WithGenericMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1431,6 +2051,23 @@ class CameraServerService final { } }; template + class WithGenericMethod_RespondResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodGeneric(21); + } + ~WithGenericMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1531,12 +2168,32 @@ class CameraServerService final { } }; template + class WithRawMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodRaw(5); + } + ~WithRawMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStartVideo(::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(5, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_SubscribeStopVideo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRaw(5); + ::grpc::Service::MarkMethodRaw(6); } ~WithRawMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1547,7 +2204,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodRaw(7); + } + ~WithRawMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStopVideo(::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(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1556,7 +2233,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1567,7 +2244,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStartVideoStreaming(::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(9, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1576,7 +2273,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(10); } ~WithRawMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1587,7 +2284,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodRaw(11); + } + ~WithRawMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondStopVideoStreaming(::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(11, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1596,7 +2313,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(12); } ~WithRawMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -1607,7 +2324,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeSetMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondSetMode() { + ::grpc::Service::MarkMethodRaw(13); + } + ~WithRawMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondSetMode(::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(13, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1616,7 +2353,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodRaw(9); + ::grpc::Service::MarkMethodRaw(14); } ~WithRawMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1627,7 +2364,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1636,7 +2373,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodRaw(10); + ::grpc::Service::MarkMethodRaw(15); } ~WithRawMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1647,7 +2384,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStorageInformation(::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(10, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(15, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1656,7 +2393,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodRaw(11); + ::grpc::Service::MarkMethodRaw(16); } ~WithRawMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1667,7 +2404,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1676,7 +2413,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodRaw(12); + ::grpc::Service::MarkMethodRaw(17); } ~WithRawMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1687,7 +2424,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondCaptureStatus(::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(12, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(17, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1696,7 +2433,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodRaw(13); + ::grpc::Service::MarkMethodRaw(18); } ~WithRawMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -1707,7 +2444,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodRaw(19); + } + ~WithRawMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondFormatStorage(::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(19, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1716,7 +2473,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodRaw(14); + ::grpc::Service::MarkMethodRaw(20); } ~WithRawMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1727,7 +2484,27 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_RespondResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodRaw(21); + } + ~WithRawMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestRespondResetSettings(::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(21, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1841,12 +2618,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodRawCallback(5, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStartVideo(context, request, response); })); + } + ~WithRawCallbackMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStartVideo( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeStopVideo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRawCallback(5, + ::grpc::Service::MarkMethodRawCallback(6, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideo(context, request); })); @@ -1863,12 +2662,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodRawCallback(7, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStopVideo(context, request, response); })); + } + ~WithRawCallbackMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStopVideo( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeStartVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(6, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideoStreaming(context, request); })); @@ -1885,12 +2706,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodRawCallback(9, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStartVideoStreaming(context, request, response); })); + } + ~WithRawCallbackMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStartVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeStopVideoStreaming : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(7, + ::grpc::Service::MarkMethodRawCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideoStreaming(context, request); })); @@ -1907,12 +2750,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodRawCallback(11, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStopVideoStreaming(context, request, response); })); + } + ~WithRawCallbackMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondStopVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeSetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodRawCallback(8, + ::grpc::Service::MarkMethodRawCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeSetMode(context, request); })); @@ -1929,12 +2794,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondSetMode() { + ::grpc::Service::MarkMethodRawCallback(13, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondSetMode(context, request, response); })); + } + ~WithRawCallbackMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondSetMode( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeStorageInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodRawCallback(9, + ::grpc::Service::MarkMethodRawCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStorageInformation(context, request); })); @@ -1956,7 +2843,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodRawCallback(10, + ::grpc::Service::MarkMethodRawCallback(15, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStorageInformation(context, request, response); })); @@ -1978,7 +2865,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodRawCallback(11, + ::grpc::Service::MarkMethodRawCallback(16, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCaptureStatus(context, request); })); @@ -2000,7 +2887,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodRawCallback(12, + ::grpc::Service::MarkMethodRawCallback(17, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondCaptureStatus(context, request, response); })); @@ -2022,7 +2909,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodRawCallback(13, + ::grpc::Service::MarkMethodRawCallback(18, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFormatStorage(context, request); })); @@ -2039,12 +2926,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodRawCallback(19, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondFormatStorage(context, request, response); })); + } + ~WithRawCallbackMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondFormatStorage( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodRawCallback(14, + ::grpc::Service::MarkMethodRawCallback(20, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeResetSettings(context, request); })); @@ -2061,6 +2970,28 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_RespondResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodRawCallback(21, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondResetSettings(context, request, response); })); + } + ~WithRawCallbackMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* RespondResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2142,12 +3073,147 @@ class CameraServerService final { virtual ::grpc::Status StreamedRespondTakePhoto(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest,::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* server_unary_streamer) = 0; }; template + class WithStreamedUnaryMethod_RespondStartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondStartVideo() { + ::grpc::Service::MarkMethodStreamed(5, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* streamer) { + return this->StreamedRespondStartVideo(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondStartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondStartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondStartVideo(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondStartVideoRequest,::mavsdk::rpc::camera_server::RespondStartVideoResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondStopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondStopVideo() { + ::grpc::Service::MarkMethodStreamed(7, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* streamer) { + return this->StreamedRespondStopVideo(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondStopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondStopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondStopVideo(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondStopVideoRequest,::mavsdk::rpc::camera_server::RespondStopVideoResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondStartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondStartVideoStreaming() { + ::grpc::Service::MarkMethodStreamed(9, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* streamer) { + return this->StreamedRespondStartVideoStreaming(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondStartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondStartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondStartVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest,::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondStopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondStopVideoStreaming() { + ::grpc::Service::MarkMethodStreamed(11, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* streamer) { + return this->StreamedRespondStopVideoStreaming(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondStopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondStopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest,::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondSetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondSetMode() { + ::grpc::Service::MarkMethodStreamed(13, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>* streamer) { + return this->StreamedRespondSetMode(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondSetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondSetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondSetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondSetMode(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondSetModeRequest,::mavsdk::rpc::camera_server::RespondSetModeResponse>* server_unary_streamer) = 0; + }; + template class WithStreamedUnaryMethod_RespondStorageInformation : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodStreamed(10, + ::grpc::Service::MarkMethodStreamed(15, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( [this](::grpc::ServerContext* context, @@ -2174,7 +3240,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodStreamed(12, + ::grpc::Service::MarkMethodStreamed(17, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( [this](::grpc::ServerContext* context, @@ -2195,7 +3261,61 @@ class CameraServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedRespondCaptureStatus(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest,::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetInformation > > > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_RespondFormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondFormatStorage() { + ::grpc::Service::MarkMethodStreamed(19, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* streamer) { + return this->StreamedRespondFormatStorage(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondFormatStorage() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondFormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondFormatStorage(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest,::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_RespondResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_RespondResetSettings() { + ::grpc::Service::MarkMethodStreamed(21, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* streamer) { + return this->StreamedRespondResetSettings(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_RespondResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status RespondResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedRespondResetSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest,::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: @@ -2256,7 +3376,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodStreamed(5, + ::grpc::Service::MarkMethodStreamed(6, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [this](::grpc::ServerContext* context, @@ -2283,7 +3403,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -2310,7 +3430,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -2337,7 +3457,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(12, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [this](::grpc::ServerContext* context, @@ -2364,7 +3484,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodStreamed(9, + ::grpc::Service::MarkMethodStreamed(14, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [this](::grpc::ServerContext* context, @@ -2391,7 +3511,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodStreamed(11, + ::grpc::Service::MarkMethodStreamed(16, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [this](::grpc::ServerContext* context, @@ -2418,7 +3538,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodStreamed(13, + ::grpc::Service::MarkMethodStreamed(18, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [this](::grpc::ServerContext* context, @@ -2445,7 +3565,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodStreamed(14, + ::grpc::Service::MarkMethodStreamed(20, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [this](::grpc::ServerContext* context, @@ -2467,7 +3587,7 @@ class CameraServerService final { virtual ::grpc::Status StreamedSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest,::mavsdk::rpc::camera_server::ResetSettingsResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 771d300e8d..16d40f225e 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -115,6 +115,40 @@ struct TakePhotoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.capture_info_)*/nullptr + , /*decltype(_impl_.take_photo_feedback_)*/ 0 +} {} +struct RespondTakePhotoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondTakePhotoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondTakePhotoRequestDefaultTypeInternal() {} + union { + RespondTakePhotoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondTakePhotoResponse::RespondTakePhotoResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondTakePhotoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondTakePhotoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondTakePhotoResponseDefaultTypeInternal() {} + union { + RespondTakePhotoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondTakePhotoResponseDefaultTypeInternal _RespondTakePhotoResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeStartVideoRequest::SubscribeStartVideoRequest( ::_pbi::ConstantInitialized) {} struct SubscribeStartVideoRequestDefaultTypeInternal { @@ -144,6 +178,38 @@ struct StartVideoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondStartVideoRequest::RespondStartVideoRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.start_video_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondStartVideoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStartVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStartVideoRequestDefaultTypeInternal() {} + union { + RespondStartVideoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStartVideoRequestDefaultTypeInternal _RespondStartVideoRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStartVideoResponse::RespondStartVideoResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondStartVideoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStartVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStartVideoResponseDefaultTypeInternal() {} + union { + RespondStartVideoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStartVideoResponseDefaultTypeInternal _RespondStartVideoResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeStopVideoRequest::SubscribeStopVideoRequest( ::_pbi::ConstantInitialized) {} struct SubscribeStopVideoRequestDefaultTypeInternal { @@ -173,6 +239,38 @@ struct StopVideoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoResponseDefaultTypeInternal _StopVideoResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondStopVideoRequest::RespondStopVideoRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stop_video_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondStopVideoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStopVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStopVideoRequestDefaultTypeInternal() {} + union { + RespondStopVideoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStopVideoRequestDefaultTypeInternal _RespondStopVideoRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStopVideoResponse::RespondStopVideoResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondStopVideoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStopVideoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStopVideoResponseDefaultTypeInternal() {} + union { + RespondStopVideoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStopVideoResponseDefaultTypeInternal _RespondStopVideoResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest( ::_pbi::ConstantInitialized) {} struct SubscribeStartVideoStreamingRequestDefaultTypeInternal { @@ -202,6 +300,38 @@ struct StartVideoStreamingResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoStreamingResponseDefaultTypeInternal _StartVideoStreamingResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondStartVideoStreamingRequest::RespondStartVideoStreamingRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.start_video_streaming_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondStartVideoStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStartVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStartVideoStreamingRequestDefaultTypeInternal() {} + union { + RespondStartVideoStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStartVideoStreamingRequestDefaultTypeInternal _RespondStartVideoStreamingRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStartVideoStreamingResponse::RespondStartVideoStreamingResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondStartVideoStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStartVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStartVideoStreamingResponseDefaultTypeInternal() {} + union { + RespondStartVideoStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStartVideoStreamingResponseDefaultTypeInternal _RespondStartVideoStreamingResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest( ::_pbi::ConstantInitialized) {} struct SubscribeStopVideoStreamingRequestDefaultTypeInternal { @@ -231,6 +361,38 @@ struct StopVideoStreamingResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondStopVideoStreamingRequest::RespondStopVideoStreamingRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.stop_video_streaming_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondStopVideoStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStopVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStopVideoStreamingRequestDefaultTypeInternal() {} + union { + RespondStopVideoStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStopVideoStreamingRequestDefaultTypeInternal _RespondStopVideoStreamingRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondStopVideoStreamingResponse::RespondStopVideoStreamingResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondStopVideoStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondStopVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondStopVideoStreamingResponseDefaultTypeInternal() {} + union { + RespondStopVideoStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondStopVideoStreamingResponseDefaultTypeInternal _RespondStopVideoStreamingResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeSetModeRequest::SubscribeSetModeRequest( ::_pbi::ConstantInitialized) {} struct SubscribeSetModeRequestDefaultTypeInternal { @@ -260,6 +422,38 @@ struct SetModeResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondSetModeRequest::RespondSetModeRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.set_mode_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondSetModeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondSetModeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondSetModeRequestDefaultTypeInternal() {} + union { + RespondSetModeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondSetModeRequestDefaultTypeInternal _RespondSetModeRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondSetModeResponse::RespondSetModeResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondSetModeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondSetModeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondSetModeResponseDefaultTypeInternal() {} + union { + RespondSetModeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondSetModeResponseDefaultTypeInternal _RespondSetModeResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest::SubscribeStorageInformationRequest( ::_pbi::ConstantInitialized) {} struct SubscribeStorageInformationRequestDefaultTypeInternal { @@ -293,7 +487,9 @@ PROTOBUF_CONSTEXPR RespondStorageInformationRequest::RespondStorageInformationRe ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} , /*decltype(_impl_._cached_size_)*/{} - , /*decltype(_impl_.storage_information_)*/nullptr} {} + , /*decltype(_impl_.storage_information_)*/nullptr + , /*decltype(_impl_.storage_information_feedback_)*/ 0 +} {} struct RespondStorageInformationRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR RespondStorageInformationRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~RespondStorageInformationRequestDefaultTypeInternal() {} @@ -354,7 +550,9 @@ PROTOBUF_CONSTEXPR RespondCaptureStatusRequest::RespondCaptureStatusRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} , /*decltype(_impl_._cached_size_)*/{} - , /*decltype(_impl_.capture_status_)*/nullptr} {} + , /*decltype(_impl_.capture_status_)*/nullptr + , /*decltype(_impl_.capture_status_feedback_)*/ 0 +} {} struct RespondCaptureStatusRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR RespondCaptureStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~RespondCaptureStatusRequestDefaultTypeInternal() {} @@ -411,6 +609,38 @@ struct FormatStorageResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FormatStorageResponseDefaultTypeInternal _FormatStorageResponse_default_instance_; template +PROTOBUF_CONSTEXPR RespondFormatStorageRequest::RespondFormatStorageRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.format_storage_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondFormatStorageRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondFormatStorageRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondFormatStorageRequestDefaultTypeInternal() {} + union { + RespondFormatStorageRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondFormatStorageRequestDefaultTypeInternal _RespondFormatStorageRequest_default_instance_; +template +PROTOBUF_CONSTEXPR RespondFormatStorageResponse::RespondFormatStorageResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct RespondFormatStorageResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondFormatStorageResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondFormatStorageResponseDefaultTypeInternal() {} + union { + RespondFormatStorageResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondFormatStorageResponseDefaultTypeInternal _RespondFormatStorageResponse_default_instance_; +template PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest::SubscribeResetSettingsRequest( ::_pbi::ConstantInitialized) {} struct SubscribeResetSettingsRequestDefaultTypeInternal { @@ -440,39 +670,37 @@ struct ResetSettingsResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; template -PROTOBUF_CONSTEXPR RespondTakePhotoRequest::RespondTakePhotoRequest( +PROTOBUF_CONSTEXPR RespondResetSettingsRequest::RespondResetSettingsRequest( ::_pbi::ConstantInitialized): _impl_{ - /*decltype(_impl_._has_bits_)*/{} - , /*decltype(_impl_._cached_size_)*/{} - , /*decltype(_impl_.capture_info_)*/nullptr - , /*decltype(_impl_.take_photo_feedback_)*/ 0 -} {} -struct RespondTakePhotoRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR RespondTakePhotoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~RespondTakePhotoRequestDefaultTypeInternal() {} + /*decltype(_impl_.reset_settings_feedback_)*/ 0 + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct RespondResetSettingsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondResetSettingsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondResetSettingsRequestDefaultTypeInternal() {} union { - RespondTakePhotoRequest _instance; + RespondResetSettingsRequest _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondTakePhotoRequestDefaultTypeInternal _RespondTakePhotoRequest_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondResetSettingsRequestDefaultTypeInternal _RespondResetSettingsRequest_default_instance_; template -PROTOBUF_CONSTEXPR RespondTakePhotoResponse::RespondTakePhotoResponse( +PROTOBUF_CONSTEXPR RespondResetSettingsResponse::RespondResetSettingsResponse( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_._has_bits_)*/{} , /*decltype(_impl_._cached_size_)*/{} , /*decltype(_impl_.camera_server_result_)*/nullptr} {} -struct RespondTakePhotoResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR RespondTakePhotoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~RespondTakePhotoResponseDefaultTypeInternal() {} +struct RespondResetSettingsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR RespondResetSettingsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~RespondResetSettingsResponseDefaultTypeInternal() {} union { - RespondTakePhotoResponse _instance; + RespondResetSettingsResponse _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondTakePhotoResponseDefaultTypeInternal _RespondTakePhotoResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RespondResetSettingsResponseDefaultTypeInternal _RespondResetSettingsResponse_default_instance_; template PROTOBUF_CONSTEXPR Information::Information( ::_pbi::ConstantInitialized): _impl_{ @@ -667,7 +895,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[37]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[51]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -729,25 +957,30 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::TakePhotoResponse, _impl_.index_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _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::camera_server::StartVideoResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_.take_photo_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_.capture_info_), + ~0u, + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _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::camera_server::StartVideoResponse, _impl_.stream_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ @@ -755,33 +988,35 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StartVideoResponse, _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::camera_server::StopVideoResponse, _impl_.stream_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StartVideoResponse, _impl_.stream_id_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoRequest, _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::camera_server::StartVideoStreamingResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoRequest, _impl_.start_video_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoResponse, _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::camera_server::StartVideoStreamingResponse, _impl_.stream_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ @@ -789,33 +1024,35 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoStreamingResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoResponse, _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::camera_server::StopVideoStreamingResponse, _impl_.stream_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoResponse, _impl_.stream_id_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeSetModeRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoRequest, _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::camera_server::SetModeResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoRequest, _impl_.stop_video_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoResponse, _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::camera_server::SetModeResponse, _impl_.mode_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ @@ -823,36 +1060,35 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformationResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StartVideoStreamingResponse, _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::camera_server::StorageInformationResponse, _impl_.storage_id_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StartVideoStreamingResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, _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::camera_server::RespondStorageInformationRequest, _impl_.storage_information_), - 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, _impl_.start_video_streaming_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, _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::camera_server::RespondStorageInformationResponse, _impl_.camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, _impl_.camera_server_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ @@ -860,36 +1096,35 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::CaptureStatusResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoStreamingResponse, _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::camera_server::CaptureStatusResponse, _impl_.reserved_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StopVideoStreamingResponse, _impl_.stream_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, _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::camera_server::RespondCaptureStatusRequest, _impl_.capture_status_), - 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, _impl_.stop_video_streaming_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, _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::camera_server::RespondCaptureStatusResponse, _impl_.camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, _impl_.camera_server_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeSetModeRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ @@ -897,52 +1132,182 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no _split_ ~0u, // no sizeof(Split) ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::FormatStorageResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetModeResponse, _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::camera_server::FormatStorageResponse, _impl_.storage_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetModeResponse, _impl_.mode_), ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondSetModeRequest, _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::camera_server::RespondSetModeRequest, _impl_.set_mode_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondSetModeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondSetModeResponse, _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::camera_server::RespondSetModeResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::ResetSettingsResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, _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::camera_server::ResetSettingsResponse, _impl_.reserved_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _internal_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformationResponse, _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::camera_server::RespondTakePhotoRequest, _impl_.take_photo_feedback_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoRequest, _impl_.capture_info_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::StorageInformationResponse, _impl_.storage_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _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::camera_server::RespondStorageInformationRequest, _impl_.storage_information_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationRequest, _impl_.storage_information_), ~0u, 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondTakePhotoResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _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::camera_server::RespondTakePhotoResponse, _impl_.camera_server_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondStorageInformationResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, _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::camera_server::CaptureStatusResponse, _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::camera_server::CaptureStatusResponse, _impl_.reserved_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _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::camera_server::RespondCaptureStatusRequest, _impl_.capture_status_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, _impl_.capture_status_), + ~0u, + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, _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::camera_server::RespondCaptureStatusResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, _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::camera_server::FormatStorageResponse, _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::camera_server::FormatStorageResponse, _impl_.storage_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondFormatStorageRequest, _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::camera_server::RespondFormatStorageRequest, _impl_.format_storage_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondFormatStorageResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondFormatStorageResponse, _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::camera_server::RespondFormatStorageResponse, _impl_.camera_server_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, _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::camera_server::ResetSettingsResponse, _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::camera_server::ResetSettingsResponse, _impl_.reserved_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondResetSettingsRequest, _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::camera_server::RespondResetSettingsRequest, _impl_.reset_settings_feedback_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondResetSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::RespondResetSettingsResponse, _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::camera_server::RespondResetSettingsResponse, _impl_.camera_server_result_), 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _internal_metadata_), @@ -1057,37 +1422,51 @@ static const ::_pbi::MigrationSchema { 29, 38, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, { 39, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, { 47, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - { 56, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, - { 64, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, - { 73, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, - { 81, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, - { 90, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, - { 98, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, - { 107, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, - { 115, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, - { 124, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, - { 132, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, - { 141, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, - { 149, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, - { 158, 167, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, - { 168, 177, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, - { 178, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, - { 186, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, - { 195, 204, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, - { 205, 214, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, - { 215, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, - { 223, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, - { 232, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, - { 240, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, - { 249, 259, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 261, 270, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 271, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 290, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 302, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 314, 328, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 334, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, - { 344, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, - { 360, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, + { 56, 66, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 68, 77, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 78, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, + { 86, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, + { 95, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoRequest)}, + { 104, 113, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoResponse)}, + { 114, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, + { 122, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, + { 131, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoRequest)}, + { 140, 149, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoResponse)}, + { 150, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, + { 158, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, + { 167, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest)}, + { 176, 185, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse)}, + { 186, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, + { 194, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, + { 203, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest)}, + { 212, 221, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse)}, + { 222, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, + { 230, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, + { 239, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeRequest)}, + { 248, 257, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeResponse)}, + { 258, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, + { 266, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, + { 275, 285, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, + { 287, 296, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, + { 297, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, + { 305, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, + { 314, 324, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, + { 326, 335, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, + { 336, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, + { 344, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, + { 353, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageRequest)}, + { 362, 371, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageResponse)}, + { 372, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, + { 380, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, + { 389, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, + { 398, 407, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, + { 408, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 427, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 439, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 451, 465, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 471, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 481, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + { 497, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1097,16 +1476,28 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_TakePhotoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStartVideoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StartVideoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStartVideoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStartVideoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStopVideoRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StopVideoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStopVideoRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStopVideoResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStartVideoStreamingRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StartVideoStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStartVideoStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStartVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStopVideoStreamingRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StopVideoStreamingResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStopVideoStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondStopVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeSetModeRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetModeResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondSetModeRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondSetModeResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeStorageInformationRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_StorageInformationResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondStorageInformationRequest_default_instance_._instance, @@ -1117,10 +1508,12 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_RespondCaptureStatusResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeFormatStorageRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_FormatStorageResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondFormatStorageRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondFormatStorageResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeResetSettingsRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_ResetSettingsResponse_default_instance_._instance, - &::mavsdk::rpc::camera_server::_RespondTakePhotoRequest_default_instance_._instance, - &::mavsdk::rpc::camera_server::_RespondTakePhotoResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondResetSettingsRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_RespondResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, &::mavsdk::rpc::camera_server::_Position_default_instance_._instance, &::mavsdk::rpc::camera_server::_Quaternion_default_instance_._instance, @@ -1142,155 +1535,220 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "sult\030\001 \001(\0132,.mavsdk.rpc.camera_server.Ca" "meraServerResult\"\033\n\031SubscribeTakePhotoRe" "quest\"\"\n\021TakePhotoResponse\022\r\n\005index\030\001 \001(" - "\005\"\034\n\032SubscribeStartVideoRequest\"\'\n\022Start" - "VideoResponse\022\021\n\tstream_id\030\001 \001(\005\"\033\n\031Subs" - "cribeStopVideoRequest\"&\n\021StopVideoRespon" - "se\022\021\n\tstream_id\030\001 \001(\005\"%\n#SubscribeStartV" - "ideoStreamingRequest\"0\n\033StartVideoStream" - "ingResponse\022\021\n\tstream_id\030\001 \001(\005\"$\n\"Subscr" - "ibeStopVideoStreamingRequest\"/\n\032StopVide" - "oStreamingResponse\022\021\n\tstream_id\030\001 \001(\005\"\031\n" - "\027SubscribeSetModeRequest\"\?\n\017SetModeRespo" - "nse\022,\n\004mode\030\001 \001(\0162\036.mavsdk.rpc.camera_se" - "rver.Mode\"$\n\"SubscribeStorageInformation" - "Request\"0\n\032StorageInformationResponse\022\022\n" - "\nstorage_id\030\001 \001(\005\"m\n RespondStorageInfor" - "mationRequest\022I\n\023storage_information\030\001 \001" - "(\0132,.mavsdk.rpc.camera_server.StorageInf" - "ormation\"o\n!RespondStorageInformationRes" - "ponse\022J\n\024camera_server_result\030\001 \001(\0132,.ma" - "vsdk.rpc.camera_server.CameraServerResul" - "t\"\037\n\035SubscribeCaptureStatusRequest\")\n\025Ca" - "ptureStatusResponse\022\020\n\010reserved\030\001 \001(\005\"^\n" - "\033RespondCaptureStatusRequest\022\?\n\016capture_" - "status\030\001 \001(\0132\'.mavsdk.rpc.camera_server." - "CaptureStatus\"j\n\034RespondCaptureStatusRes" - "ponse\022J\n\024camera_server_result\030\001 \001(\0132,.ma" - "vsdk.rpc.camera_server.CameraServerResul" - "t\"\037\n\035SubscribeFormatStorageRequest\"+\n\025Fo" - "rmatStorageResponse\022\022\n\nstorage_id\030\001 \001(\005\"" - "\037\n\035SubscribeResetSettingsRequest\")\n\025Rese" - "tSettingsResponse\022\020\n\010reserved\030\001 \001(\005\"\240\001\n\027" - "RespondTakePhotoRequest\022H\n\023take_photo_fe" - "edback\030\001 \001(\0162+.mavsdk.rpc.camera_server." - "TakePhotoFeedback\022;\n\014capture_info\030\002 \001(\0132" - "%.mavsdk.rpc.camera_server.CaptureInfo\"f" - "\n\030RespondTakePhotoResponse\022J\n\024camera_ser" - "ver_result\030\001 \001(\0132,.mavsdk.rpc.camera_ser" - "ver.CameraServerResult\"\276\002\n\013Information\022\023" - "\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022" - "\030\n\020firmware_version\030\003 \001(\t\022\027\n\017focal_lengt" - "h_mm\030\004 \001(\002\022!\n\031horizontal_sensor_size_mm\030" - "\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030\006 \001(\002\022 " - "\n\030horizontal_resolution_px\030\007 \001(\r\022\036\n\026vert" - "ical_resolution_px\030\010 \001(\r\022\017\n\007lens_id\030\t \001(" - "\r\022\037\n\027definition_file_version\030\n \001(\r\022\033\n\023de" - "finition_file_uri\030\013 \001(\t\"q\n\010Position\022\024\n\014l" - "atitude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001" - "\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023relativ" - "e_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 " - "\001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n" - "\013CaptureInfo\0224\n\010position\030\001 \001(\0132\".mavsdk." - "rpc.camera_server.Position\022A\n\023attitude_q" - "uaternion\030\002 \001(\0132$.mavsdk.rpc.camera_serv" - "er.Quaternion\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis" - "_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_ur" - "l\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n\006result" - "\030\001 \001(\01623.mavsdk.rpc.camera_server.Camera" - "ServerResult.Result\022\022\n\nresult_str\030\002 \001(\t\"" - "\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT" - "_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013RE" - "SULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESULT" - "_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT_W" - "RONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005" - "\n\022StorageInformation\022\030\n\020used_storage_mib" - "\030\001 \001(\002\022\035\n\025available_storage_mib\030\002 \001(\002\022\031\n" - "\021total_storage_mib\030\003 \001(\002\022R\n\016storage_stat" - "us\030\004 \001(\0162:.mavsdk.rpc.camera_server.Stor" - "ageInformation.StorageStatus\022\022\n\nstorage_" - "id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628.mavsdk." - "rpc.camera_server.StorageInformation.Sto" - "rageType\022\030\n\020read_speed_mib_s\030\007 \001(\002\022\031\n\021wr" - "ite_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022" - " \n\034STORAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STO" - "RAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STA" - "TUS_FORMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SU" - "PPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYP" - "E_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022" - "\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MIC" - "ROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_T" - "YPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030\n\020image_" - "interval_s\030\001 \001(\002\022\030\n\020recording_time_s\030\002 \001" - "(\002\022\036\n\026available_capacity_mib\030\003 \001(\002\022I\n\014im" - "age_status\030\004 \001(\01623.mavsdk.rpc.camera_ser" - "ver.CaptureStatus.ImageStatus\022I\n\014video_s" - "tatus\030\005 \001(\01623.mavsdk.rpc.camera_server.C" - "aptureStatus.VideoStatus\022\023\n\013image_count\030" - "\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_STATUS_ID" - "LE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_PROGRESS" - "\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE\020\002\022%\n!IM" - "AGE_STATUS_INTERVAL_IN_PROGRESS\020\003\"J\n\013Vid" - "eoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO" - "_STATUS_CAPTURE_IN_PROGRESS\020\001*\216\001\n\021TakePh" - "otoFeedback\022\037\n\033TAKE_PHOTO_FEEDBACK_UNKNO" - "WN\020\000\022\032\n\026TAKE_PHOTO_FEEDBACK_OK\020\001\022\034\n\030TAKE" - "_PHOTO_FEEDBACK_BUSY\020\002\022\036\n\032TAKE_PHOTO_FEE" - "DBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000" - "\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\0022\260\020\n\023Cam" - "eraServerService\022y\n\016SetInformation\022/.mav" - "sdk.rpc.camera_server.SetInformationRequ" - "est\0320.mavsdk.rpc.camera_server.SetInform" - "ationResponse\"\004\200\265\030\001\022v\n\rSetInProgress\022..m" - "avsdk.rpc.camera_server.SetInProgressReq" - "uest\032/.mavsdk.rpc.camera_server.SetInPro" - "gressResponse\"\004\200\265\030\001\022~\n\022SubscribeTakePhot" - "o\0223.mavsdk.rpc.camera_server.SubscribeTa" - "kePhotoRequest\032+.mavsdk.rpc.camera_serve" - "r.TakePhotoResponse\"\004\200\265\030\0000\001\022\177\n\020RespondTa" - "kePhoto\0221.mavsdk.rpc.camera_server.Respo" - "ndTakePhotoRequest\0322.mavsdk.rpc.camera_s" - "erver.RespondTakePhotoResponse\"\004\200\265\030\001\022\201\001\n" - "\023SubscribeStartVideo\0224.mavsdk.rpc.camera" - "_server.SubscribeStartVideoRequest\032,.mav" - "sdk.rpc.camera_server.StartVideoResponse" - "\"\004\200\265\030\0000\001\022~\n\022SubscribeStopVideo\0223.mavsdk." - "rpc.camera_server.SubscribeStopVideoRequ" - "est\032+.mavsdk.rpc.camera_server.StopVideo" - "Response\"\004\200\265\030\0000\001\022\234\001\n\034SubscribeStartVideo" - "Streaming\022=.mavsdk.rpc.camera_server.Sub" - "scribeStartVideoStreamingRequest\0325.mavsd" - "k.rpc.camera_server.StartVideoStreamingR" - "esponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStopVideoSt" - "reaming\022<.mavsdk.rpc.camera_server.Subsc" - "ribeStopVideoStreamingRequest\0324.mavsdk.r" - "pc.camera_server.StopVideoStreamingRespo" - "nse\"\004\200\265\030\0000\001\022x\n\020SubscribeSetMode\0221.mavsdk" - ".rpc.camera_server.SubscribeSetModeReque" - "st\032).mavsdk.rpc.camera_server.SetModeRes" - "ponse\"\004\200\265\030\0000\001\022\231\001\n\033SubscribeStorageInform" - "ation\022<.mavsdk.rpc.camera_server.Subscri" - "beStorageInformationRequest\0324.mavsdk.rpc" - ".camera_server.StorageInformationRespons" - "e\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInformation\022" - ":.mavsdk.rpc.camera_server.RespondStorag" - "eInformationRequest\032;.mavsdk.rpc.camera_" - "server.RespondStorageInformationResponse" - "\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227.mavs" - "dk.rpc.camera_server.SubscribeCaptureSta" - "tusRequest\032/.mavsdk.rpc.camera_server.Ca" - "ptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024RespondC" - "aptureStatus\0225.mavsdk.rpc.camera_server." - "RespondCaptureStatusRequest\0326.mavsdk.rpc" - ".camera_server.RespondCaptureStatusRespo" - "nse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorage\0227.m" - "avsdk.rpc.camera_server.SubscribeFormatS" - "torageRequest\032/.mavsdk.rpc.camera_server" - ".FormatStorageResponse\"\004\200\265\030\0000\001\022\212\001\n\026Subsc" - "ribeResetSettings\0227.mavsdk.rpc.camera_se" - "rver.SubscribeResetSettingsRequest\032/.mav" - "sdk.rpc.camera_server.ResetSettingsRespo" - "nse\"\004\200\265\030\0000\001B,\n\027io.mavsdk.camera_serverB\021" - "CameraServerProtob\006proto3" + "\005\"\235\001\n\027RespondTakePhotoRequest\022E\n\023take_ph" + "oto_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_s" + "erver.CameraFeedback\022;\n\014capture_info\030\002 \001" + "(\0132%.mavsdk.rpc.camera_server.CaptureInf" + "o\"f\n\030RespondTakePhotoResponse\022J\n\024camera_" + "server_result\030\001 \001(\0132,.mavsdk.rpc.camera_" + "server.CameraServerResult\"\034\n\032SubscribeSt" + "artVideoRequest\"\'\n\022StartVideoResponse\022\021\n" + "\tstream_id\030\001 \001(\005\"b\n\030RespondStartVideoReq" + "uest\022F\n\024start_video_feedback\030\001 \001(\0162(.mav" + "sdk.rpc.camera_server.CameraFeedback\"g\n\031" + "RespondStartVideoResponse\022J\n\024camera_serv" + "er_result\030\001 \001(\0132,.mavsdk.rpc.camera_serv" + "er.CameraServerResult\"\033\n\031SubscribeStopVi" + "deoRequest\"&\n\021StopVideoResponse\022\021\n\tstrea" + "m_id\030\001 \001(\005\"`\n\027RespondStopVideoRequest\022E\n" + "\023stop_video_feedback\030\001 \001(\0162(.mavsdk.rpc." + "camera_server.CameraFeedback\"f\n\030RespondS" + "topVideoResponse\022J\n\024camera_server_result" + "\030\001 \001(\0132,.mavsdk.rpc.camera_server.Camera" + "ServerResult\"%\n#SubscribeStartVideoStrea" + "mingRequest\"0\n\033StartVideoStreamingRespon" + "se\022\021\n\tstream_id\030\001 \001(\005\"u\n!RespondStartVid" + "eoStreamingRequest\022P\n\036start_video_stream" + "ing_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_s" + "erver.CameraFeedback\"p\n\"RespondStartVide" + "oStreamingResponse\022J\n\024camera_server_resu" + "lt\030\001 \001(\0132,.mavsdk.rpc.camera_server.Came" + "raServerResult\"$\n\"SubscribeStopVideoStre" + "amingRequest\"/\n\032StopVideoStreamingRespon" + "se\022\021\n\tstream_id\030\001 \001(\005\"s\n RespondStopVide" + "oStreamingRequest\022O\n\035stop_video_streamin" + "g_feedback\030\001 \001(\0162(.mavsdk.rpc.camera_ser" + "ver.CameraFeedback\"o\n!RespondStopVideoSt" + "reamingResponse\022J\n\024camera_server_result\030" + "\001 \001(\0132,.mavsdk.rpc.camera_server.CameraS" + "erverResult\"\031\n\027SubscribeSetModeRequest\"\?" + "\n\017SetModeResponse\022,\n\004mode\030\001 \001(\0162\036.mavsdk" + ".rpc.camera_server.Mode\"\\\n\025RespondSetMod" + "eRequest\022C\n\021set_mode_feedback\030\001 \001(\0162(.ma" + "vsdk.rpc.camera_server.CameraFeedback\"d\n" + "\026RespondSetModeResponse\022J\n\024camera_server" + "_result\030\001 \001(\0132,.mavsdk.rpc.camera_server" + ".CameraServerResult\"$\n\"SubscribeStorageI" + "nformationRequest\"0\n\032StorageInformationR" + "esponse\022\022\n\nstorage_id\030\001 \001(\005\"\275\001\n RespondS" + "torageInformationRequest\022N\n\034storage_info" + "rmation_feedback\030\001 \001(\0162(.mavsdk.rpc.came" + "ra_server.CameraFeedback\022I\n\023storage_info" + "rmation\030\002 \001(\0132,.mavsdk.rpc.camera_server" + ".StorageInformation\"o\n!RespondStorageInf" + "ormationResponse\022J\n\024camera_server_result" + "\030\001 \001(\0132,.mavsdk.rpc.camera_server.Camera" + "ServerResult\"\037\n\035SubscribeCaptureStatusRe" + "quest\")\n\025CaptureStatusResponse\022\020\n\010reserv" + "ed\030\001 \001(\005\"\251\001\n\033RespondCaptureStatusRequest" + "\022I\n\027capture_status_feedback\030\001 \001(\0162(.mavs" + "dk.rpc.camera_server.CameraFeedback\022\?\n\016c" + "apture_status\030\002 \001(\0132\'.mavsdk.rpc.camera_" + "server.CaptureStatus\"j\n\034RespondCaptureSt" + "atusResponse\022J\n\024camera_server_result\030\001 \001" + "(\0132,.mavsdk.rpc.camera_server.CameraServ" + "erResult\"\037\n\035SubscribeFormatStorageReques" + "t\"+\n\025FormatStorageResponse\022\022\n\nstorage_id" + "\030\001 \001(\005\"h\n\033RespondFormatStorageRequest\022I\n" + "\027format_storage_feedback\030\001 \001(\0162(.mavsdk." + "rpc.camera_server.CameraFeedback\"j\n\034Resp" + "ondFormatStorageResponse\022J\n\024camera_serve" + "r_result\030\001 \001(\0132,.mavsdk.rpc.camera_serve" + "r.CameraServerResult\"\037\n\035SubscribeResetSe" + "ttingsRequest\")\n\025ResetSettingsResponse\022\020" + "\n\010reserved\030\001 \001(\005\"h\n\033RespondResetSettings" + "Request\022I\n\027reset_settings_feedback\030\001 \001(\016" + "2(.mavsdk.rpc.camera_server.CameraFeedba" + "ck\"j\n\034RespondResetSettingsResponse\022J\n\024ca" + "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" + "mera_server.CameraServerResult\"\276\002\n\013Infor" + "mation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_nam" + "e\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017foc" + "al_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_" + "size_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm" + "\030\006 \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r" + "\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens" + "_id\030\t \001(\r\022\037\n\027definition_file_version\030\n \001" + "(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Posit" + "ion\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_d" + "eg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n" + "\023relative_altitude_m\030\004 \001(\002\"8\n\nQuaternion" + "\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004" + " \001(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\"" + ".mavsdk.rpc.camera_server.Position\022A\n\023at" + "titude_quaternion\030\002 \001(\0132$.mavsdk.rpc.cam" + "era_server.Quaternion\022\023\n\013time_utc_us\030\003 \001" + "(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n" + "\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C" + "\n\006result\030\001 \001(\01623.mavsdk.rpc.camera_serve" + "r.CameraServerResult.Result\022\022\n\nresult_st" + "r\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022" + "\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS" + "\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020" + "\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025" + "RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYS" + "TEM\020\010\"\214\005\n\022StorageInformation\022\030\n\020used_sto" + "rage_mib\030\001 \001(\002\022\035\n\025available_storage_mib\030" + "\002 \001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016stor" + "age_status\030\004 \001(\0162:.mavsdk.rpc.camera_ser" + "ver.StorageInformation.StorageStatus\022\022\n\n" + "storage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628" + ".mavsdk.rpc.camera_server.StorageInforma" + "tion.StorageType\022\030\n\020read_speed_mib_s\030\007 \001" + "(\002\022\031\n\021write_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorag" + "eStatus\022 \n\034STORAGE_STATUS_NOT_AVAILABLE\020" + "\000\022\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STO" + "RAGE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STATU" + "S_NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STO" + "RAGE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_" + "STICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_" + "TYPE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022S" + "TORAGE_TYPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030" + "\n\020image_interval_s\030\001 \001(\002\022\030\n\020recording_ti" + "me_s\030\002 \001(\002\022\036\n\026available_capacity_mib\030\003 \001" + "(\002\022I\n\014image_status\030\004 \001(\01623.mavsdk.rpc.ca" + "mera_server.CaptureStatus.ImageStatus\022I\n" + "\014video_status\030\005 \001(\01623.mavsdk.rpc.camera_" + "server.CaptureStatus.VideoStatus\022\023\n\013imag" + "e_count\030\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_S" + "TATUS_IDLE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_" + "PROGRESS\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE" + "\020\002\022%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\020" + "\003\"J\n\013VideoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022" + "$\n VIDEO_STATUS_CAPTURE_IN_PROGRESS\020\001*{\n" + "\016CameraFeedback\022\033\n\027CAMERA_FEEDBACK_UNKNO" + "WN\020\000\022\026\n\022CAMERA_FEEDBACK_OK\020\001\022\030\n\024CAMERA_F" + "EEDBACK_BUSY\020\002\022\032\n\026CAMERA_FEEDBACK_FAILED" + "\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHO" + "TO\020\001\022\016\n\nMODE_VIDEO\020\0022\212\030\n\023CameraServerSer" + "vice\022y\n\016SetInformation\022/.mavsdk.rpc.came" + "ra_server.SetInformationRequest\0320.mavsdk" + ".rpc.camera_server.SetInformationRespons" + "e\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.ca" + "mera_server.SetInProgressRequest\032/.mavsd" + "k.rpc.camera_server.SetInProgressRespons" + "e\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.r" + "pc.camera_server.SubscribeTakePhotoReque" + "st\032+.mavsdk.rpc.camera_server.TakePhotoR" + "esponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.ma" + "vsdk.rpc.camera_server.RespondTakePhotoR" + "equest\0322.mavsdk.rpc.camera_server.Respon" + "dTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeSt" + "artVideo\0224.mavsdk.rpc.camera_server.Subs" + "cribeStartVideoRequest\032,.mavsdk.rpc.came" + "ra_server.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n" + "\021RespondStartVideo\0222.mavsdk.rpc.camera_s" + "erver.RespondStartVideoRequest\0323.mavsdk." + "rpc.camera_server.RespondStartVideoRespo" + "nse\"\004\200\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk" + ".rpc.camera_server.SubscribeStopVideoReq" + "uest\032+.mavsdk.rpc.camera_server.StopVide" + "oResponse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221." + "mavsdk.rpc.camera_server.RespondStopVide" + "oRequest\0322.mavsdk.rpc.camera_server.Resp" + "ondStopVideoResponse\"\004\200\265\030\001\022\234\001\n\034Subscribe" + "StartVideoStreaming\022=.mavsdk.rpc.camera_" + "server.SubscribeStartVideoStreamingReque" + "st\0325.mavsdk.rpc.camera_server.StartVideo" + "StreamingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondSta" + "rtVideoStreaming\022;.mavsdk.rpc.camera_ser" + "ver.RespondStartVideoStreamingRequest\032<." + "mavsdk.rpc.camera_server.RespondStartVid" + "eoStreamingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeS" + "topVideoStreaming\022<.mavsdk.rpc.camera_se" + "rver.SubscribeStopVideoStreamingRequest\032" + "4.mavsdk.rpc.camera_server.StopVideoStre" + "amingResponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVid" + "eoStreaming\022:.mavsdk.rpc.camera_server.R" + "espondStopVideoStreamingRequest\032;.mavsdk" + ".rpc.camera_server.RespondStopVideoStrea" + "mingResponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221" + ".mavsdk.rpc.camera_server.SubscribeSetMo" + "deRequest\032).mavsdk.rpc.camera_server.Set" + "ModeResponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/" + ".mavsdk.rpc.camera_server.RespondSetMode" + "Request\0320.mavsdk.rpc.camera_server.Respo" + "ndSetModeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeSto" + "rageInformation\022<.mavsdk.rpc.camera_serv" + "er.SubscribeStorageInformationRequest\0324." + "mavsdk.rpc.camera_server.StorageInformat" + "ionResponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageIn" + "formation\022:.mavsdk.rpc.camera_server.Res" + "pondStorageInformationRequest\032;.mavsdk.r" + "pc.camera_server.RespondStorageInformati" + "onResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureSta" + "tus\0227.mavsdk.rpc.camera_server.Subscribe" + "CaptureStatusRequest\032/.mavsdk.rpc.camera" + "_server.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001" + "\n\024RespondCaptureStatus\0225.mavsdk.rpc.came" + "ra_server.RespondCaptureStatusRequest\0326." + "mavsdk.rpc.camera_server.RespondCaptureS" + "tatusResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatS" + "torage\0227.mavsdk.rpc.camera_server.Subscr" + "ibeFormatStorageRequest\032/.mavsdk.rpc.cam" + "era_server.FormatStorageResponse\"\004\200\265\030\0000\001" + "\022\213\001\n\024RespondFormatStorage\0225.mavsdk.rpc.c" + "amera_server.RespondFormatStorageRequest" + "\0326.mavsdk.rpc.camera_server.RespondForma" + "tStorageResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeRese" + "tSettings\0227.mavsdk.rpc.camera_server.Sub" + "scribeResetSettingsRequest\032/.mavsdk.rpc." + "camera_server.ResetSettingsResponse\"\004\200\265\030" + "\0000\001\022\213\001\n\024RespondResetSettings\0225.mavsdk.rp" + "c.camera_server.RespondResetSettingsRequ" + "est\0326.mavsdk.rpc.camera_server.RespondRe" + "setSettingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.c" + "amera_serverB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1300,13 +1758,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 6425, + 9039, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 37, + 51, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -1485,11 +1943,11 @@ constexpr int CaptureStatus::VideoStatus_ARRAYSIZE; #endif // (__cplusplus < 201703) && // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) -const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* TakePhotoFeedback_descriptor() { +const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* CameraFeedback_descriptor() { ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto); return file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[5]; } -bool TakePhotoFeedback_IsValid(int value) { +bool CameraFeedback_IsValid(int value) { switch (value) { case 0: case 1: @@ -2516,71 +2974,57 @@ ::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { } // =================================================================== -class SubscribeStartVideoRequest::_Internal { +class RespondTakePhotoRequest::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const RespondTakePhotoRequest* msg); + static void set_has_capture_info(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -SubscribeStartVideoRequest::SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) -} -SubscribeStartVideoRequest::SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStartVideoRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); +const ::mavsdk::rpc::camera_server::CaptureInfo& +RespondTakePhotoRequest::_Internal::capture_info(const RespondTakePhotoRequest* msg) { + return *msg->_impl_.capture_info_; } -// =================================================================== - -class StartVideoResponse::_Internal { - public: -}; - -StartVideoResponse::StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondTakePhotoRequest::RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) } -StartVideoResponse::StartVideoResponse(const StartVideoResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoResponse) +RespondTakePhotoRequest::RespondTakePhotoRequest(const RespondTakePhotoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondTakePhotoRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_info_){nullptr} + , decltype(_impl_.take_photo_feedback_) {} + }; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.capture_info_ = new ::mavsdk::rpc::camera_server::CaptureInfo(*from._impl_.capture_info_); + } + _this->_impl_.take_photo_feedback_ = from._impl_.take_photo_feedback_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) } -inline void StartVideoResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondTakePhotoRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.stream_id_) { 0 } - + decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_info_){nullptr} + , decltype(_impl_.take_photo_feedback_) { 0 } + }; } -StartVideoResponse::~StartVideoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoResponse) +RespondTakePhotoRequest::~RespondTakePhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -2588,34 +3032,52 @@ StartVideoResponse::~StartVideoResponse() { SharedDtor(); } -inline void StartVideoResponse::SharedDtor() { +inline void RespondTakePhotoRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.capture_info_; } -void StartVideoResponse::SetCachedSize(int size) const { +void RespondTakePhotoRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void StartVideoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoResponse) +void RespondTakePhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.stream_id_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.capture_info_ != nullptr); + _impl_.capture_info_->Clear(); + } + _impl_.take_photo_feedback_ = 0; + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* StartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 stream_id = 1; + // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_take_photo_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_capture_info(), ptr); CHK_(ptr); } else { goto handle_unusual; @@ -2637,6 +3099,7 @@ const char* StartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseCon CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -2644,155 +3107,161 @@ const char* StartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseCon #undef CHK_ } -::uint8_t* StartVideoResponse::_InternalSerialize( +::uint8_t* RespondTakePhotoRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; + if (this->_internal_take_photo_feedback() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_stream_id(), target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_take_photo_feedback(), target); } - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { - target = ::_pbi::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.camera_server.StartVideoResponse) + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(2, _Internal::capture_info(this), + _Internal::capture_info(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondTakePhotoRequest) return target; } -::size_t StartVideoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoResponse) +::size_t RespondTakePhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_stream_id()); + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.capture_info_); + } + + // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; + if (this->_internal_take_photo_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_take_photo_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StartVideoResponse::MergeImpl + RespondTakePhotoRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoRequest::GetClassData() const { return &_class_data_; } -void StartVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoResponse) +void RespondTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_stream_id() != 0) { - _this->_internal_set_stream_id(from._internal_stream_id()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_capture_info()->::mavsdk::rpc::camera_server::CaptureInfo::MergeFrom( + from._internal_capture_info()); + } + if (from._internal_take_photo_feedback() != 0) { + _this->_internal_set_take_photo_feedback(from._internal_take_photo_feedback()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void StartVideoResponse::CopyFrom(const StartVideoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoResponse) +void RespondTakePhotoRequest::CopyFrom(const RespondTakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool StartVideoResponse::IsInitialized() const { +bool RespondTakePhotoRequest::IsInitialized() const { return true; } -void StartVideoResponse::InternalSwap(StartVideoResponse* other) { +void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.stream_id_, other->_impl_.stream_id_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.take_photo_feedback_) + + sizeof(RespondTakePhotoRequest::_impl_.take_photo_feedback_) + - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.capture_info_)>( + reinterpret_cast(&_impl_.capture_info_), + reinterpret_cast(&other->_impl_.capture_info_)); } -::PROTOBUF_NAMESPACE_ID::Metadata StartVideoResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); } // =================================================================== -class SubscribeStopVideoRequest::_Internal { +class RespondTakePhotoResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondTakePhotoResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -SubscribeStopVideoRequest::SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) -} -SubscribeStopVideoRequest::SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStopVideoRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondTakePhotoResponse::_Internal::camera_server_result(const RespondTakePhotoResponse* msg) { + return *msg->_impl_.camera_server_result_; } -// =================================================================== - -class StopVideoResponse::_Internal { - public: -}; - -StopVideoResponse::StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondTakePhotoResponse::RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) } -StopVideoResponse::StopVideoResponse(const StopVideoResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoResponse) +RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondTakePhotoResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) } -inline void StopVideoResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondTakePhotoResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.stream_id_) { 0 } - + decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} }; } -StopVideoResponse::~StopVideoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoResponse) +RespondTakePhotoResponse::~RespondTakePhotoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -2800,34 +3269,41 @@ StopVideoResponse::~StopVideoResponse() { SharedDtor(); } -inline void StopVideoResponse::SharedDtor() { +inline void RespondTakePhotoResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void StopVideoResponse::SetCachedSize(int size) const { +void RespondTakePhotoResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void StopVideoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoResponse) +void RespondTakePhotoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.stream_id_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* StopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 stream_id = 1; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); CHK_(ptr); } else { goto handle_unusual; @@ -2849,6 +3325,7 @@ const char* StopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseCont CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -2856,114 +3333,118 @@ const char* StopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseCont #undef CHK_ } -::uint8_t* StopVideoResponse::_InternalSerialize( +::uint8_t* RespondTakePhotoResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_stream_id(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.StopVideoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondTakePhotoResponse) return target; } -::size_t StopVideoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoResponse) +::size_t RespondTakePhotoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_stream_id()); + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StopVideoResponse::MergeImpl + RespondTakePhotoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoResponse::GetClassData() const { return &_class_data_; } -void StopVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoResponse) +void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_stream_id() != 0) { - _this->_internal_set_stream_id(from._internal_stream_id()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void StopVideoResponse::CopyFrom(const StopVideoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoResponse) +void RespondTakePhotoResponse::CopyFrom(const RespondTakePhotoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool StopVideoResponse::IsInitialized() const { +bool RespondTakePhotoResponse::IsInitialized() const { return true; } -void StopVideoResponse::InternalSwap(StopVideoResponse* other) { +void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.stream_id_, other->_impl_.stream_id_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); } // =================================================================== -class SubscribeStartVideoStreamingRequest::_Internal { +class SubscribeStartVideoRequest::_Internal { public: }; -SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeStartVideoRequest::SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) } -SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from) +SubscribeStartVideoRequest::SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStartVideoStreamingRequest* const _this = this; (void)_this; + SubscribeStartVideoRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoStreamingRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoStreamingRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoRequest::GetClassData() const { return &_class_data_; } @@ -2971,30 +3452,30 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoStreamingRe -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoStreamingRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); } // =================================================================== -class StartVideoStreamingResponse::_Internal { +class StartVideoResponse::_Internal { public: }; -StartVideoStreamingResponse::StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +StartVideoResponse::StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoResponse) } -StartVideoStreamingResponse::StartVideoStreamingResponse(const StartVideoStreamingResponse& from) +StartVideoResponse::StartVideoResponse(const StartVideoResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoResponse) } -inline void StartVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { +inline void StartVideoResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ decltype(_impl_.stream_id_) { 0 } @@ -3003,8 +3484,8 @@ inline void StartVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { }; } -StartVideoStreamingResponse::~StartVideoStreamingResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +StartVideoResponse::~StartVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3012,16 +3493,16 @@ StartVideoStreamingResponse::~StartVideoStreamingResponse() { SharedDtor(); } -inline void StartVideoStreamingResponse::SharedDtor() { +inline void StartVideoResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); } -void StartVideoStreamingResponse::SetCachedSize(int size) const { +void StartVideoResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void StartVideoStreamingResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +void StartVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -3030,7 +3511,7 @@ void StartVideoStreamingResponse::Clear() { _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* StartVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* StartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; @@ -3068,9 +3549,9 @@ const char* StartVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi: #undef CHK_ } -::uint8_t* StartVideoStreamingResponse::_InternalSerialize( +::uint8_t* StartVideoResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -3085,12 +3566,12 @@ ::uint8_t* StartVideoStreamingResponse::_InternalSerialize( target = ::_pbi::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.camera_server.StartVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.StartVideoResponse) return target; } -::size_t StartVideoStreamingResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +::size_t StartVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -3106,17 +3587,17 @@ ::size_t StartVideoStreamingResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoStreamingResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StartVideoStreamingResponse::MergeImpl + StartVideoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoStreamingResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoResponse::GetClassData() const { return &_class_data_; } -void StartVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoStreamingResponse) +void StartVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -3127,96 +3608,58 @@ void StartVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void StartVideoStreamingResponse::CopyFrom(const StartVideoStreamingResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) +void StartVideoResponse::CopyFrom(const StartVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool StartVideoStreamingResponse::IsInitialized() const { +bool StartVideoResponse::IsInitialized() const { return true; } -void StartVideoStreamingResponse::InternalSwap(StartVideoStreamingResponse* other) { +void StartVideoResponse::InternalSwap(StartVideoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.stream_id_, other->_impl_.stream_id_); } -::PROTOBUF_NAMESPACE_ID::Metadata StartVideoStreamingResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); -} -// =================================================================== - -class SubscribeStopVideoStreamingRequest::_Internal { - public: -}; - -SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) -} -SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStopVideoStreamingRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoStreamingRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoStreamingRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoStreamingRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata StartVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); } // =================================================================== -class StopVideoStreamingResponse::_Internal { +class RespondStartVideoRequest::_Internal { public: }; -StopVideoStreamingResponse::StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStartVideoRequest::RespondStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStartVideoRequest) } -StopVideoStreamingResponse::StopVideoStreamingResponse(const StopVideoStreamingResponse& from) +RespondStartVideoRequest::RespondStartVideoRequest(const RespondStartVideoRequest& from) : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStartVideoRequest) } -inline void StopVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondStartVideoRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.stream_id_) { 0 } + decltype(_impl_.start_video_feedback_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; } -StopVideoStreamingResponse::~StopVideoStreamingResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +RespondStartVideoRequest::~RespondStartVideoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStartVideoRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3224,35 +3667,36 @@ StopVideoStreamingResponse::~StopVideoStreamingResponse() { SharedDtor(); } -inline void StopVideoStreamingResponse::SharedDtor() { +inline void RespondStartVideoRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); } -void StopVideoStreamingResponse::SetCachedSize(int size) const { +void RespondStartVideoRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void StopVideoStreamingResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +void RespondStartVideoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStartVideoRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.stream_id_ = 0; + _impl_.start_video_feedback_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* StopVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondStartVideoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 stream_id = 1; + // .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); + _internal_set_start_video_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); } else { goto handle_unusual; } @@ -3280,155 +3724,135 @@ const char* StopVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi:: #undef CHK_ } -::uint8_t* StopVideoStreamingResponse::_InternalSerialize( +::uint8_t* RespondStartVideoRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStartVideoRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; + if (this->_internal_start_video_feedback() != 0) { target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_stream_id(), target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_start_video_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStartVideoRequest) return target; } -::size_t StopVideoStreamingResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +::size_t RespondStartVideoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStartVideoRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_stream_id()); + // .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; + if (this->_internal_start_video_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_start_video_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoStreamingResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStartVideoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StopVideoStreamingResponse::MergeImpl + RespondStartVideoRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoStreamingResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStartVideoRequest::GetClassData() const { return &_class_data_; } -void StopVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoStreamingResponse) +void RespondStartVideoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStartVideoRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_stream_id() != 0) { - _this->_internal_set_stream_id(from._internal_stream_id()); + if (from._internal_start_video_feedback() != 0) { + _this->_internal_set_start_video_feedback(from._internal_start_video_feedback()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void StopVideoStreamingResponse::CopyFrom(const StopVideoStreamingResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +void RespondStartVideoRequest::CopyFrom(const RespondStartVideoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStartVideoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool StopVideoStreamingResponse::IsInitialized() const { +bool RespondStartVideoRequest::IsInitialized() const { return true; } -void StopVideoStreamingResponse::InternalSwap(StopVideoStreamingResponse* other) { +void RespondStartVideoRequest::InternalSwap(RespondStartVideoRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.stream_id_, other->_impl_.stream_id_); + swap(_impl_.start_video_feedback_, other->_impl_.start_video_feedback_); } -::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); } // =================================================================== -class SubscribeSetModeRequest::_Internal { +class RespondStartVideoResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStartVideoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStartVideoResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -SubscribeSetModeRequest::SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) -} -SubscribeSetModeRequest::SubscribeSetModeRequest(const SubscribeSetModeRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeSetModeRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeSetModeRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeSetModeRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeSetModeRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondStartVideoResponse::_Internal::camera_server_result(const RespondStartVideoResponse* msg) { + return *msg->_impl_.camera_server_result_; } -// =================================================================== - -class SetModeResponse::_Internal { - public: -}; - -SetModeResponse::SetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStartVideoResponse::RespondStartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetModeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStartVideoResponse) } -SetModeResponse::SetModeResponse(const SetModeResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetModeResponse) +RespondStartVideoResponse::RespondStartVideoResponse(const RespondStartVideoResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondStartVideoResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStartVideoResponse) } -inline void SetModeResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondStartVideoResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.mode_) { 0 } - + decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} }; } -SetModeResponse::~SetModeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetModeResponse) +RespondStartVideoResponse::~RespondStartVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStartVideoResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3436,36 +3860,42 @@ SetModeResponse::~SetModeResponse() { SharedDtor(); } -inline void SetModeResponse::SharedDtor() { +inline void RespondStartVideoResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void SetModeResponse::SetCachedSize(int size) const { +void RespondStartVideoResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void SetModeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetModeResponse) +void RespondStartVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStartVideoResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.mode_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* SetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondStartVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.Mode mode = 1; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); CHK_(ptr); - _internal_set_mode(static_cast<::mavsdk::rpc::camera_server::Mode>(val)); } else { goto handle_unusual; } @@ -3486,6 +3916,7 @@ const char* SetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContex CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -3493,113 +3924,118 @@ const char* SetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContex #undef CHK_ } -::uint8_t* SetModeResponse::_InternalSerialize( +::uint8_t* RespondStartVideoResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetModeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStartVideoResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.camera_server.Mode mode = 1; - if (this->_internal_mode() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_mode(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.SetModeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStartVideoResponse) return target; } -::size_t SetModeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetModeResponse) +::size_t RespondStartVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStartVideoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.Mode mode = 1; - if (this->_internal_mode() != 0) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetModeResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStartVideoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - SetModeResponse::MergeImpl + RespondStartVideoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetModeResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStartVideoResponse::GetClassData() const { return &_class_data_; } -void SetModeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.SetModeResponse) +void RespondStartVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStartVideoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_mode() != 0) { - _this->_internal_set_mode(from._internal_mode()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void SetModeResponse::CopyFrom(const SetModeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetModeResponse) +void RespondStartVideoResponse::CopyFrom(const RespondStartVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStartVideoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool SetModeResponse::IsInitialized() const { +bool RespondStartVideoResponse::IsInitialized() const { return true; } -void SetModeResponse::InternalSwap(SetModeResponse* other) { +void RespondStartVideoResponse::InternalSwap(RespondStartVideoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.mode_, other->_impl_.mode_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata SetModeResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); } // =================================================================== -class SubscribeStorageInformationRequest::_Internal { +class SubscribeStopVideoRequest::_Internal { public: }; -SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeStopVideoRequest::SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) } -SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from) +SubscribeStopVideoRequest::SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeStorageInformationRequest* const _this = this; (void)_this; + SubscribeStopVideoRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStorageInformationRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStorageInformationRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoRequest::GetClassData() const { return &_class_data_; } @@ -3607,40 +4043,40 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStorageInformationReq -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStorageInformationRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); } // =================================================================== -class StorageInformationResponse::_Internal { +class StopVideoResponse::_Internal { public: }; -StorageInformationResponse::StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +StopVideoResponse::StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoResponse) } -StorageInformationResponse::StorageInformationResponse(const StorageInformationResponse& from) +StopVideoResponse::StopVideoResponse(const StopVideoResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoResponse) } -inline void StorageInformationResponse::SharedCtor(::_pb::Arena* arena) { +inline void StopVideoResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.storage_id_) { 0 } + decltype(_impl_.stream_id_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; } -StorageInformationResponse::~StorageInformationResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StorageInformationResponse) +StopVideoResponse::~StopVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3648,34 +4084,34 @@ StorageInformationResponse::~StorageInformationResponse() { SharedDtor(); } -inline void StorageInformationResponse::SharedDtor() { +inline void StopVideoResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); } -void StorageInformationResponse::SetCachedSize(int size) const { +void StopVideoResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void StorageInformationResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StorageInformationResponse) +void StopVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.storage_id_ = 0; + _impl_.stream_id_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* StorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* StopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 storage_id = 1; + // int32 stream_id = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else { goto handle_unusual; @@ -3704,136 +4140,117 @@ const char* StorageInformationResponse::_InternalParse(const char* ptr, ::_pbi:: #undef CHK_ } -::uint8_t* StorageInformationResponse::_InternalSerialize( +::uint8_t* StopVideoResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_storage_id(), target); + 1, this->_internal_stream_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.StopVideoResponse) return target; } -::size_t StorageInformationResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StorageInformationResponse) +::size_t StopVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_storage_id()); + this->_internal_stream_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StorageInformationResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - StorageInformationResponse::MergeImpl + StopVideoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StorageInformationResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoResponse::GetClassData() const { return &_class_data_; } -void StorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StorageInformationResponse) +void StopVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_storage_id() != 0) { - _this->_internal_set_storage_id(from._internal_storage_id()); + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void StorageInformationResponse::CopyFrom(const StorageInformationResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StorageInformationResponse) +void StopVideoResponse::CopyFrom(const StopVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool StorageInformationResponse::IsInitialized() const { +bool StopVideoResponse::IsInitialized() const { return true; } -void StorageInformationResponse::InternalSwap(StorageInformationResponse* other) { +void StopVideoResponse::InternalSwap(StopVideoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.storage_id_, other->_impl_.storage_id_); + swap(_impl_.stream_id_, other->_impl_.stream_id_); } -::PROTOBUF_NAMESPACE_ID::Metadata StorageInformationResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); } // =================================================================== -class RespondStorageInformationRequest::_Internal { +class RespondStopVideoRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::StorageInformation& storage_information(const RespondStorageInformationRequest* msg); - static void set_has_storage_information(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::StorageInformation& -RespondStorageInformationRequest::_Internal::storage_information(const RespondStorageInformationRequest* msg) { - return *msg->_impl_.storage_information_; -} -RespondStorageInformationRequest::RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStopVideoRequest::RespondStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStopVideoRequest) } -RespondStorageInformationRequest::RespondStorageInformationRequest(const RespondStorageInformationRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondStorageInformationRequest* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.storage_information_){nullptr}}; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.storage_information_ = new ::mavsdk::rpc::camera_server::StorageInformation(*from._impl_.storage_information_); - } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +RespondStopVideoRequest::RespondStopVideoRequest(const RespondStopVideoRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStopVideoRequest) } -inline void RespondStorageInformationRequest::SharedCtor(::_pb::Arena* arena) { +inline void RespondStopVideoRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} + decltype(_impl_.stop_video_feedback_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.storage_information_){nullptr} }; } -RespondStorageInformationRequest::~RespondStorageInformationRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +RespondStopVideoRequest::~RespondStopVideoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStopVideoRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3841,42 +4258,36 @@ RespondStorageInformationRequest::~RespondStorageInformationRequest() { SharedDtor(); } -inline void RespondStorageInformationRequest::SharedDtor() { +inline void RespondStopVideoRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.storage_information_; } -void RespondStorageInformationRequest::SetCachedSize(int size) const { +void RespondStopVideoRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondStorageInformationRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +void RespondStopVideoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStopVideoRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.storage_information_ != nullptr); - _impl_.storage_information_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.stop_video_feedback_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondStorageInformationRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondStopVideoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_storage_information(), ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); + _internal_set_stop_video_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); } else { goto handle_unusual; } @@ -3897,7 +4308,6 @@ const char* RespondStorageInformationRequest::_InternalParse(const char* ptr, :: CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -3905,117 +4315,112 @@ const char* RespondStorageInformationRequest::_InternalParse(const char* ptr, :: #undef CHK_ } -::uint8_t* RespondStorageInformationRequest::_InternalSerialize( +::uint8_t* RespondStopVideoRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStopVideoRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::storage_information(this), - _Internal::storage_information(this).GetCachedSize(), target, stream); + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; + if (this->_internal_stop_video_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_stop_video_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondStorageInformationRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStopVideoRequest) return target; } -::size_t RespondStorageInformationRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +::size_t RespondStopVideoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStopVideoRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; + if (this->_internal_stop_video_feedback() != 0) { total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.storage_information_); + ::_pbi::WireFormatLite::EnumSize(this->_internal_stop_video_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStopVideoRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondStorageInformationRequest::MergeImpl + RespondStopVideoRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStopVideoRequest::GetClassData() const { return &_class_data_; } -void RespondStorageInformationRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationRequest) +void RespondStopVideoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStopVideoRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_storage_information()->::mavsdk::rpc::camera_server::StorageInformation::MergeFrom( - from._internal_storage_information()); + if (from._internal_stop_video_feedback() != 0) { + _this->_internal_set_stop_video_feedback(from._internal_stop_video_feedback()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondStorageInformationRequest::CopyFrom(const RespondStorageInformationRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +void RespondStopVideoRequest::CopyFrom(const RespondStopVideoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStopVideoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondStorageInformationRequest::IsInitialized() const { +bool RespondStopVideoRequest::IsInitialized() const { return true; } -void RespondStorageInformationRequest::InternalSwap(RespondStorageInformationRequest* other) { +void RespondStopVideoRequest::InternalSwap(RespondStopVideoRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.storage_information_, other->_impl_.storage_information_); + swap(_impl_.stop_video_feedback_, other->_impl_.stop_video_feedback_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); } // =================================================================== -class RespondStorageInformationResponse::_Internal { +class RespondStopVideoResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStorageInformationResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(RespondStopVideoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStopVideoResponse* msg); static void set_has_camera_server_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; const ::mavsdk::rpc::camera_server::CameraServerResult& -RespondStorageInformationResponse::_Internal::camera_server_result(const RespondStorageInformationResponse* msg) { +RespondStopVideoResponse::_Internal::camera_server_result(const RespondStopVideoResponse* msg) { return *msg->_impl_.camera_server_result_; } -RespondStorageInformationResponse::RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStopVideoResponse::RespondStopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStopVideoResponse) } -RespondStorageInformationResponse::RespondStorageInformationResponse(const RespondStorageInformationResponse& from) +RespondStopVideoResponse::RespondStopVideoResponse(const RespondStopVideoResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondStorageInformationResponse* const _this = this; (void)_this; + RespondStopVideoResponse* const _this = this; (void)_this; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){from._impl_._has_bits_} , /*decltype(_impl_._cached_size_)*/{} @@ -4025,10 +4430,10 @@ RespondStorageInformationResponse::RespondStorageInformationResponse(const Respo if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStopVideoResponse) } -inline void RespondStorageInformationResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondStopVideoResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){} @@ -4037,8 +4442,8 @@ inline void RespondStorageInformationResponse::SharedCtor(::_pb::Arena* arena) { }; } -RespondStorageInformationResponse::~RespondStorageInformationResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +RespondStopVideoResponse::~RespondStopVideoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStopVideoResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4046,17 +4451,17 @@ RespondStorageInformationResponse::~RespondStorageInformationResponse() { SharedDtor(); } -inline void RespondStorageInformationResponse::SharedDtor() { +inline void RespondStopVideoResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void RespondStorageInformationResponse::SetCachedSize(int size) const { +void RespondStopVideoResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondStorageInformationResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +void RespondStopVideoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStopVideoResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -4070,7 +4475,7 @@ void RespondStorageInformationResponse::Clear() { _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondStorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondStopVideoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { @@ -4110,9 +4515,9 @@ const char* RespondStorageInformationResponse::_InternalParse(const char* ptr, : #undef CHK_ } -::uint8_t* RespondStorageInformationResponse::_InternalSerialize( +::uint8_t* RespondStopVideoResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStopVideoResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -4128,12 +4533,12 @@ ::uint8_t* RespondStorageInformationResponse::_InternalSerialize( target = ::_pbi::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.camera_server.RespondStorageInformationResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondStopVideoResponse) return target; } -::size_t RespondStorageInformationResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +::size_t RespondStopVideoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStopVideoResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -4151,17 +4556,17 @@ ::size_t RespondStorageInformationResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStopVideoResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondStorageInformationResponse::MergeImpl + RespondStopVideoResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStopVideoResponse::GetClassData() const { return &_class_data_; } -void RespondStorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationResponse) +void RespondStopVideoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStopVideoResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -4173,55 +4578,55 @@ void RespondStorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Messa _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondStorageInformationResponse::CopyFrom(const RespondStorageInformationResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +void RespondStopVideoResponse::CopyFrom(const RespondStopVideoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStopVideoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondStorageInformationResponse::IsInitialized() const { +bool RespondStopVideoResponse::IsInitialized() const { return true; } -void RespondStorageInformationResponse::InternalSwap(RespondStorageInformationResponse* other) { +void RespondStopVideoResponse::InternalSwap(RespondStopVideoResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); } // =================================================================== -class SubscribeCaptureStatusRequest::_Internal { +class SubscribeStartVideoStreamingRequest::_Internal { public: }; -SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) } -SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from) +SubscribeStartVideoStreamingRequest::SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from) : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeCaptureStatusRequest* const _this = this; (void)_this; + SubscribeStartVideoStreamingRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeCaptureStatusRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStartVideoStreamingRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeCaptureStatusRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoStreamingRequest::GetClassData() const { return &_class_data_; } @@ -4229,40 +4634,40 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeCaptureStatusRequest: -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeCaptureStatusRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); } // =================================================================== -class CaptureStatusResponse::_Internal { +class StartVideoStreamingResponse::_Internal { public: }; -CaptureStatusResponse::CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +StartVideoStreamingResponse::StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) } -CaptureStatusResponse::CaptureStatusResponse(const CaptureStatusResponse& from) +StartVideoStreamingResponse::StartVideoStreamingResponse(const StartVideoStreamingResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) } -inline void CaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { +inline void StartVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.reserved_) { 0 } + decltype(_impl_.stream_id_) { 0 } , /*decltype(_impl_._cached_size_)*/{} }; } -CaptureStatusResponse::~CaptureStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureStatusResponse) +StartVideoStreamingResponse::~StartVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StartVideoStreamingResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4270,34 +4675,34 @@ CaptureStatusResponse::~CaptureStatusResponse() { SharedDtor(); } -inline void CaptureStatusResponse::SharedDtor() { +inline void StartVideoStreamingResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); } -void CaptureStatusResponse::SetCachedSize(int size) const { +void StartVideoStreamingResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void CaptureStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureStatusResponse) +void StartVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.reserved_ = 0; + _impl_.stream_id_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* CaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* StartVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 reserved = 1; + // int32 stream_id = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.reserved_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else { goto handle_unusual; @@ -4326,136 +4731,3034 @@ const char* CaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::Parse #undef CHK_ } -::uint8_t* CaptureStatusResponse::_InternalSerialize( +::uint8_t* StartVideoStreamingResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 reserved = 1; - if (this->_internal_reserved() != 0) { + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_reserved(), target); + 1, this->_internal_stream_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.StartVideoStreamingResponse) return target; } -::size_t CaptureStatusResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureStatusResponse) +::size_t StartVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 reserved = 1; - if (this->_internal_reserved() != 0) { + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_reserved()); + this->_internal_stream_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureStatusResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StartVideoStreamingResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - CaptureStatusResponse::MergeImpl + StartVideoStreamingResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureStatusResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StartVideoStreamingResponse::GetClassData() const { return &_class_data_; } -void CaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureStatusResponse) +void StartVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StartVideoStreamingResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_reserved() != 0) { - _this->_internal_set_reserved(from._internal_reserved()); + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void CaptureStatusResponse::CopyFrom(const CaptureStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureStatusResponse) +void StartVideoStreamingResponse::CopyFrom(const StartVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StartVideoStreamingResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool CaptureStatusResponse::IsInitialized() const { +bool StartVideoStreamingResponse::IsInitialized() const { return true; } -void CaptureStatusResponse::InternalSwap(CaptureStatusResponse* other) { +void StartVideoStreamingResponse::InternalSwap(StartVideoStreamingResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.reserved_, other->_impl_.reserved_); + swap(_impl_.stream_id_, other->_impl_.stream_id_); } -::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatusResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata StartVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); } // =================================================================== -class RespondCaptureStatusRequest::_Internal { +class RespondStartVideoStreamingRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status(const RespondCaptureStatusRequest* msg); - static void set_has_capture_status(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::CaptureStatus& -RespondCaptureStatusRequest::_Internal::capture_status(const RespondCaptureStatusRequest* msg) { - return *msg->_impl_.capture_status_; -} -RespondCaptureStatusRequest::RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondStartVideoStreamingRequest::RespondStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) } -RespondCaptureStatusRequest::RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondCaptureStatusRequest* const _this = this; (void)_this; +RespondStartVideoStreamingRequest::RespondStartVideoStreamingRequest(const RespondStartVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) +} + +inline void RespondStartVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} + decltype(_impl_.start_video_streaming_feedback_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_status_){nullptr}}; + }; +} - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.capture_status_ = new ::mavsdk::rpc::camera_server::CaptureStatus(*from._impl_.capture_status_); +RespondStartVideoStreamingRequest::~RespondStartVideoStreamingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + SharedDtor(); +} + +inline void RespondStartVideoStreamingRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void RespondStartVideoStreamingRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStartVideoStreamingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.start_video_streaming_feedback_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStartVideoStreamingRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_start_video_streaming_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStartVideoStreamingRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; + if (this->_internal_start_video_streaming_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_start_video_streaming_feedback(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStartVideoStreamingRequest) + return target; +} + +::size_t RespondStartVideoStreamingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; + if (this->_internal_start_video_streaming_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_start_video_streaming_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStartVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStartVideoStreamingRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStartVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + +void RespondStartVideoStreamingRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStartVideoStreamingRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_start_video_streaming_feedback() != 0) { + _this->_internal_set_start_video_streaming_feedback(from._internal_start_video_streaming_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStartVideoStreamingRequest::CopyFrom(const RespondStartVideoStreamingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStartVideoStreamingRequest::IsInitialized() const { + return true; +} + +void RespondStartVideoStreamingRequest::InternalSwap(RespondStartVideoStreamingRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.start_video_streaming_feedback_, other->_impl_.start_video_streaming_feedback_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); +} +// =================================================================== + +class RespondStartVideoStreamingResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStartVideoStreamingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStartVideoStreamingResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondStartVideoStreamingResponse::_Internal::camera_server_result(const RespondStartVideoStreamingResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondStartVideoStreamingResponse::RespondStartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) +} +RespondStartVideoStreamingResponse::RespondStartVideoStreamingResponse(const RespondStartVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondStartVideoStreamingResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) +} + +inline void RespondStartVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondStartVideoStreamingResponse::~RespondStartVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondStartVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondStartVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStartVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStartVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStartVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStartVideoStreamingResponse) + return target; +} + +::size_t RespondStartVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStartVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStartVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStartVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void RespondStartVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStartVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStartVideoStreamingResponse::CopyFrom(const RespondStartVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStartVideoStreamingResponse::IsInitialized() const { + return true; +} + +void RespondStartVideoStreamingResponse::InternalSwap(RespondStartVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); +} +// =================================================================== + +class SubscribeStopVideoStreamingRequest::_Internal { + public: +}; + +SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) +} +SubscribeStopVideoStreamingRequest::SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStopVideoStreamingRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStopVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); +} +// =================================================================== + +class StopVideoStreamingResponse::_Internal { + public: +}; + +StopVideoStreamingResponse::StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +} +StopVideoStreamingResponse::StopVideoStreamingResponse(const StopVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) +} + +inline void StopVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stream_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StopVideoStreamingResponse::~StopVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StopVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StopVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StopVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stream_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StopVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 stream_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.stream_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StopVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_stream_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StopVideoStreamingResponse) + return target; +} + +::size_t StopVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 stream_id = 1; + if (this->_internal_stream_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_stream_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StopVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StopVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StopVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void StopVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StopVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stream_id() != 0) { + _this->_internal_set_stream_id(from._internal_stream_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StopVideoStreamingResponse::CopyFrom(const StopVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StopVideoStreamingResponse::IsInitialized() const { + return true; +} + +void StopVideoStreamingResponse::InternalSwap(StopVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.stream_id_, other->_impl_.stream_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); +} +// =================================================================== + +class RespondStopVideoStreamingRequest::_Internal { + public: +}; + +RespondStopVideoStreamingRequest::RespondStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) +} +RespondStopVideoStreamingRequest::RespondStopVideoStreamingRequest(const RespondStopVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) +} + +inline void RespondStopVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.stop_video_streaming_feedback_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +RespondStopVideoStreamingRequest::~RespondStopVideoStreamingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondStopVideoStreamingRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void RespondStopVideoStreamingRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStopVideoStreamingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.stop_video_streaming_feedback_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStopVideoStreamingRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_stop_video_streaming_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStopVideoStreamingRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; + if (this->_internal_stop_video_streaming_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_stop_video_streaming_feedback(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStopVideoStreamingRequest) + return target; +} + +::size_t RespondStopVideoStreamingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; + if (this->_internal_stop_video_streaming_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_stop_video_streaming_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStopVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStopVideoStreamingRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStopVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + +void RespondStopVideoStreamingRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStopVideoStreamingRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_stop_video_streaming_feedback() != 0) { + _this->_internal_set_stop_video_streaming_feedback(from._internal_stop_video_streaming_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStopVideoStreamingRequest::CopyFrom(const RespondStopVideoStreamingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStopVideoStreamingRequest::IsInitialized() const { + return true; +} + +void RespondStopVideoStreamingRequest::InternalSwap(RespondStopVideoStreamingRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.stop_video_streaming_feedback_, other->_impl_.stop_video_streaming_feedback_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); +} +// =================================================================== + +class RespondStopVideoStreamingResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStopVideoStreamingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStopVideoStreamingResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondStopVideoStreamingResponse::_Internal::camera_server_result(const RespondStopVideoStreamingResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondStopVideoStreamingResponse::RespondStopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) +} +RespondStopVideoStreamingResponse::RespondStopVideoStreamingResponse(const RespondStopVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondStopVideoStreamingResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) +} + +inline void RespondStopVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondStopVideoStreamingResponse::~RespondStopVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondStopVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondStopVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStopVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStopVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStopVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStopVideoStreamingResponse) + return target; +} + +::size_t RespondStopVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStopVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStopVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStopVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void RespondStopVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStopVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStopVideoStreamingResponse::CopyFrom(const RespondStopVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStopVideoStreamingResponse::IsInitialized() const { + return true; +} + +void RespondStopVideoStreamingResponse::InternalSwap(RespondStopVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]); +} +// =================================================================== + +class SubscribeSetModeRequest::_Internal { + public: +}; + +SubscribeSetModeRequest::SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) +} +SubscribeSetModeRequest::SubscribeSetModeRequest(const SubscribeSetModeRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeSetModeRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeSetModeRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeSetModeRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeSetModeRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeSetModeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); +} +// =================================================================== + +class SetModeResponse::_Internal { + public: +}; + +SetModeResponse::SetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetModeResponse) +} +SetModeResponse::SetModeResponse(const SetModeResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetModeResponse) +} + +inline void SetModeResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.mode_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +SetModeResponse::~SetModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetModeResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetModeResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SetModeResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetModeResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.mode_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.Mode mode = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_mode(static_cast<::mavsdk::rpc::camera_server::Mode>(val)); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetModeResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetModeResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Mode mode = 1; + if (this->_internal_mode() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_mode(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.SetModeResponse) + return target; +} + +::size_t SetModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetModeResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.Mode mode = 1; + if (this->_internal_mode() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetModeResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetModeResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetModeResponse::GetClassData() const { return &_class_data_; } + + +void SetModeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.SetModeResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_mode() != 0) { + _this->_internal_set_mode(from._internal_mode()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetModeResponse::CopyFrom(const SetModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetModeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetModeResponse::IsInitialized() const { + return true; +} + +void SetModeResponse::InternalSwap(SetModeResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.mode_, other->_impl_.mode_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetModeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); +} +// =================================================================== + +class RespondSetModeRequest::_Internal { + public: +}; + +RespondSetModeRequest::RespondSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondSetModeRequest) +} +RespondSetModeRequest::RespondSetModeRequest(const RespondSetModeRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondSetModeRequest) +} + +inline void RespondSetModeRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.set_mode_feedback_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +RespondSetModeRequest::~RespondSetModeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondSetModeRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondSetModeRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void RespondSetModeRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondSetModeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondSetModeRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.set_mode_feedback_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondSetModeRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_set_mode_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondSetModeRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondSetModeRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; + if (this->_internal_set_mode_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_set_mode_feedback(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondSetModeRequest) + return target; +} + +::size_t RespondSetModeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondSetModeRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; + if (this->_internal_set_mode_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_set_mode_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondSetModeRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondSetModeRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondSetModeRequest::GetClassData() const { return &_class_data_; } + + +void RespondSetModeRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondSetModeRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_set_mode_feedback() != 0) { + _this->_internal_set_set_mode_feedback(from._internal_set_mode_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondSetModeRequest::CopyFrom(const RespondSetModeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondSetModeRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondSetModeRequest::IsInitialized() const { + return true; +} + +void RespondSetModeRequest::InternalSwap(RespondSetModeRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.set_mode_feedback_, other->_impl_.set_mode_feedback_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondSetModeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); +} +// =================================================================== + +class RespondSetModeResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondSetModeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondSetModeResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondSetModeResponse::_Internal::camera_server_result(const RespondSetModeResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondSetModeResponse::RespondSetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondSetModeResponse) +} +RespondSetModeResponse::RespondSetModeResponse(const RespondSetModeResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondSetModeResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondSetModeResponse) +} + +inline void RespondSetModeResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondSetModeResponse::~RespondSetModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondSetModeResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondSetModeResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondSetModeResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondSetModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondSetModeResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondSetModeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondSetModeResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondSetModeResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondSetModeResponse) + return target; +} + +::size_t RespondSetModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondSetModeResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondSetModeResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondSetModeResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondSetModeResponse::GetClassData() const { return &_class_data_; } + + +void RespondSetModeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondSetModeResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondSetModeResponse::CopyFrom(const RespondSetModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondSetModeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondSetModeResponse::IsInitialized() const { + return true; +} + +void RespondSetModeResponse::InternalSwap(RespondSetModeResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondSetModeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); +} +// =================================================================== + +class SubscribeStorageInformationRequest::_Internal { + public: +}; + +SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) +} +SubscribeStorageInformationRequest::SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeStorageInformationRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeStorageInformationRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStorageInformationRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStorageInformationRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); +} +// =================================================================== + +class StorageInformationResponse::_Internal { + public: +}; + +StorageInformationResponse::StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) +} +StorageInformationResponse::StorageInformationResponse(const StorageInformationResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.StorageInformationResponse) +} + +inline void StorageInformationResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.storage_id_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +StorageInformationResponse::~StorageInformationResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.StorageInformationResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void StorageInformationResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void StorageInformationResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void StorageInformationResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.StorageInformationResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.storage_id_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* StorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 storage_id = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* StorageInformationResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.StorageInformationResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_storage_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.StorageInformationResponse) + return target; +} + +::size_t StorageInformationResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.StorageInformationResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData StorageInformationResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + StorageInformationResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*StorageInformationResponse::GetClassData() const { return &_class_data_; } + + +void StorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.StorageInformationResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void StorageInformationResponse::CopyFrom(const StorageInformationResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.StorageInformationResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StorageInformationResponse::IsInitialized() const { + return true; +} + +void StorageInformationResponse::InternalSwap(StorageInformationResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.storage_id_, other->_impl_.storage_id_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata StorageInformationResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); +} +// =================================================================== + +class RespondStorageInformationRequest::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::StorageInformation& storage_information(const RespondStorageInformationRequest* msg); + static void set_has_storage_information(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::StorageInformation& +RespondStorageInformationRequest::_Internal::storage_information(const RespondStorageInformationRequest* msg) { + return *msg->_impl_.storage_information_; +} +RespondStorageInformationRequest::RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +} +RespondStorageInformationRequest::RespondStorageInformationRequest(const RespondStorageInformationRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondStorageInformationRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.storage_information_){nullptr} + , decltype(_impl_.storage_information_feedback_) {} + }; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.storage_information_ = new ::mavsdk::rpc::camera_server::StorageInformation(*from._impl_.storage_information_); + } + _this->_impl_.storage_information_feedback_ = from._impl_.storage_information_feedback_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) +} + +inline void RespondStorageInformationRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.storage_information_){nullptr} + , decltype(_impl_.storage_information_feedback_) { 0 } + + }; +} + +RespondStorageInformationRequest::~RespondStorageInformationRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondStorageInformationRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.storage_information_; +} + +void RespondStorageInformationRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStorageInformationRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.storage_information_ != nullptr); + _impl_.storage_information_->Clear(); + } + _impl_.storage_information_feedback_ = 0; + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStorageInformationRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_storage_information_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_storage_information(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStorageInformationRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; + if (this->_internal_storage_information_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_storage_information_feedback(), target); + } + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(2, _Internal::storage_information(this), + _Internal::storage_information(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStorageInformationRequest) + return target; +} + +::size_t RespondStorageInformationRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.storage_information_); + } + + // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; + if (this->_internal_storage_information_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_information_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStorageInformationRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationRequest::GetClassData() const { return &_class_data_; } + + +void RespondStorageInformationRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_storage_information()->::mavsdk::rpc::camera_server::StorageInformation::MergeFrom( + from._internal_storage_information()); + } + if (from._internal_storage_information_feedback() != 0) { + _this->_internal_set_storage_information_feedback(from._internal_storage_information_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStorageInformationRequest::CopyFrom(const RespondStorageInformationRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStorageInformationRequest::IsInitialized() const { + return true; +} + +void RespondStorageInformationRequest::InternalSwap(RespondStorageInformationRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(RespondStorageInformationRequest, _impl_.storage_information_feedback_) + + sizeof(RespondStorageInformationRequest::_impl_.storage_information_feedback_) + - PROTOBUF_FIELD_OFFSET(RespondStorageInformationRequest, _impl_.storage_information_)>( + reinterpret_cast(&_impl_.storage_information_), + reinterpret_cast(&other->_impl_.storage_information_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); +} +// =================================================================== + +class RespondStorageInformationResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondStorageInformationResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondStorageInformationResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondStorageInformationResponse::_Internal::camera_server_result(const RespondStorageInformationResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondStorageInformationResponse::RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +} +RespondStorageInformationResponse::RespondStorageInformationResponse(const RespondStorageInformationResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondStorageInformationResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) +} + +inline void RespondStorageInformationResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondStorageInformationResponse::~RespondStorageInformationResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondStorageInformationResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondStorageInformationResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondStorageInformationResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondStorageInformationResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondStorageInformationResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondStorageInformationResponse) + return target; +} + +::size_t RespondStorageInformationResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondStorageInformationResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondStorageInformationResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondStorageInformationResponse::GetClassData() const { return &_class_data_; } + + +void RespondStorageInformationResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondStorageInformationResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondStorageInformationResponse::CopyFrom(const RespondStorageInformationResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondStorageInformationResponse::IsInitialized() const { + return true; +} + +void RespondStorageInformationResponse::InternalSwap(RespondStorageInformationResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); +} +// =================================================================== + +class SubscribeCaptureStatusRequest::_Internal { + public: +}; + +SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) +} +SubscribeCaptureStatusRequest::SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeCaptureStatusRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeCaptureStatusRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeCaptureStatusRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeCaptureStatusRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); +} +// =================================================================== + +class CaptureStatusResponse::_Internal { + public: +}; + +CaptureStatusResponse::CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) +} +CaptureStatusResponse::CaptureStatusResponse(const CaptureStatusResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.CaptureStatusResponse) +} + +inline void CaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.reserved_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; +} + +CaptureStatusResponse::~CaptureStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.CaptureStatusResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void CaptureStatusResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); +} + +void CaptureStatusResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void CaptureStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.reserved_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* CaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // int32 reserved = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.reserved_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* CaptureStatusResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_reserved(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.CaptureStatusResponse) + return target; +} + +::size_t CaptureStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 reserved = 1; + if (this->_internal_reserved() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_reserved()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData CaptureStatusResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + CaptureStatusResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*CaptureStatusResponse::GetClassData() const { return &_class_data_; } + + +void CaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.CaptureStatusResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_reserved() != 0) { + _this->_internal_set_reserved(from._internal_reserved()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void CaptureStatusResponse::CopyFrom(const CaptureStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.CaptureStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CaptureStatusResponse::IsInitialized() const { + return true; +} + +void CaptureStatusResponse::InternalSwap(CaptureStatusResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + + swap(_impl_.reserved_, other->_impl_.reserved_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatusResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]); +} +// =================================================================== + +class RespondCaptureStatusRequest::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status(const RespondCaptureStatusRequest* msg); + static void set_has_capture_status(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CaptureStatus& +RespondCaptureStatusRequest::_Internal::capture_status(const RespondCaptureStatusRequest* msg) { + return *msg->_impl_.capture_status_; +} +RespondCaptureStatusRequest::RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +} +RespondCaptureStatusRequest::RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondCaptureStatusRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_status_){nullptr} + , decltype(_impl_.capture_status_feedback_) {} + }; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.capture_status_ = new ::mavsdk::rpc::camera_server::CaptureStatus(*from._impl_.capture_status_); + } + _this->_impl_.capture_status_feedback_ = from._impl_.capture_status_feedback_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +} + +inline void RespondCaptureStatusRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.capture_status_){nullptr} + , decltype(_impl_.capture_status_feedback_) { 0 } + + }; +} + +RespondCaptureStatusRequest::~RespondCaptureStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondCaptureStatusRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.capture_status_; +} + +void RespondCaptureStatusRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondCaptureStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.capture_status_ != nullptr); + _impl_.capture_status_->Clear(); + } + _impl_.capture_status_feedback_ = 0; + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondCaptureStatusRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + _internal_set_capture_status_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); + } else { + goto handle_unusual; + } + continue; + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + ptr = ctx->ParseMessage(_internal_mutable_capture_status(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondCaptureStatusRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; + if (this->_internal_capture_status_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_capture_status_feedback(), target); + } + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(2, _Internal::capture_status(this), + _Internal::capture_status(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondCaptureStatusRequest) + return target; +} + +::size_t RespondCaptureStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.capture_status_); + } + + // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; + if (this->_internal_capture_status_feedback() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_capture_status_feedback()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondCaptureStatusRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusRequest::GetClassData() const { return &_class_data_; } + + +void RespondCaptureStatusRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_capture_status()->::mavsdk::rpc::camera_server::CaptureStatus::MergeFrom( + from._internal_capture_status()); + } + if (from._internal_capture_status_feedback() != 0) { + _this->_internal_set_capture_status_feedback(from._internal_capture_status_feedback()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondCaptureStatusRequest::CopyFrom(const RespondCaptureStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondCaptureStatusRequest::IsInitialized() const { + return true; +} + +void RespondCaptureStatusRequest::InternalSwap(RespondCaptureStatusRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(RespondCaptureStatusRequest, _impl_.capture_status_feedback_) + + sizeof(RespondCaptureStatusRequest::_impl_.capture_status_feedback_) + - PROTOBUF_FIELD_OFFSET(RespondCaptureStatusRequest, _impl_.capture_status_)>( + reinterpret_cast(&_impl_.capture_status_), + reinterpret_cast(&other->_impl_.capture_status_)); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[34]); +} +// =================================================================== + +class RespondCaptureStatusResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondCaptureStatusResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondCaptureStatusResponse::_Internal::camera_server_result(const RespondCaptureStatusResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +RespondCaptureStatusResponse::RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +} +RespondCaptureStatusResponse::RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondCaptureStatusResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +} + +inline void RespondCaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +RespondCaptureStatusResponse::~RespondCaptureStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void RespondCaptureStatusResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void RespondCaptureStatusResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void RespondCaptureStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* RespondCaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* RespondCaptureStatusResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.RespondCaptureStatusResponse) + return target; +} + +::size_t RespondCaptureStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + RespondCaptureStatusResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusResponse::GetClassData() const { return &_class_data_; } + + +void RespondCaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void RespondCaptureStatusResponse::CopyFrom(const RespondCaptureStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool RespondCaptureStatusResponse::IsInitialized() const { + return true; +} + +void RespondCaptureStatusResponse::InternalSwap(RespondCaptureStatusResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[35]); +} +// =================================================================== + +class SubscribeFormatStorageRequest::_Internal { + public: +}; + +SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) +} +SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeFormatStorageRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeFormatStorageRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeFormatStorageRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeFormatStorageRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[36]); +} +// =================================================================== + +class FormatStorageResponse::_Internal { + public: +}; + +FormatStorageResponse::FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) +} +FormatStorageResponse::FormatStorageResponse(const FormatStorageResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) } -inline void RespondCaptureStatusRequest::SharedCtor(::_pb::Arena* arena) { +inline void FormatStorageResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} + decltype(_impl_.storage_id_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_status_){nullptr} }; } -RespondCaptureStatusRequest::~RespondCaptureStatusRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +FormatStorageResponse::~FormatStorageResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.FormatStorageResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4463,41 +7766,34 @@ RespondCaptureStatusRequest::~RespondCaptureStatusRequest() { SharedDtor(); } -inline void RespondCaptureStatusRequest::SharedDtor() { +inline void FormatStorageResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.capture_status_; } -void RespondCaptureStatusRequest::SetCachedSize(int size) const { +void FormatStorageResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondCaptureStatusRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +void FormatStorageResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.FormatStorageResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.capture_status_ != nullptr); - _impl_.capture_status_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.storage_id_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondCaptureStatusRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* FormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; + // int32 storage_id = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_capture_status(), ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else { goto handle_unusual; @@ -4519,7 +7815,6 @@ const char* RespondCaptureStatusRequest::_InternalParse(const char* ptr, ::_pbi: CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -4527,140 +7822,117 @@ const char* RespondCaptureStatusRequest::_InternalParse(const char* ptr, ::_pbi: #undef CHK_ } -::uint8_t* RespondCaptureStatusRequest::_InternalSerialize( +::uint8_t* FormatStorageResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.FormatStorageResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::capture_status(this), - _Internal::capture_status(this).GetCachedSize(), target, stream); + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 1, this->_internal_storage_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondCaptureStatusRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.FormatStorageResponse) return target; } -::size_t RespondCaptureStatusRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +::size_t FormatStorageResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.FormatStorageResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.capture_status_); + // int32 storage_id = 1; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData FormatStorageResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondCaptureStatusRequest::MergeImpl + FormatStorageResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*FormatStorageResponse::GetClassData() const { return &_class_data_; } -void RespondCaptureStatusRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusRequest) +void FormatStorageResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.FormatStorageResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_capture_status()->::mavsdk::rpc::camera_server::CaptureStatus::MergeFrom( - from._internal_capture_status()); + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondCaptureStatusRequest::CopyFrom(const RespondCaptureStatusRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) +void FormatStorageResponse::CopyFrom(const FormatStorageResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.FormatStorageResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondCaptureStatusRequest::IsInitialized() const { +bool FormatStorageResponse::IsInitialized() const { return true; } -void RespondCaptureStatusRequest::InternalSwap(RespondCaptureStatusRequest* other) { +void FormatStorageResponse::InternalSwap(FormatStorageResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.capture_status_, other->_impl_.capture_status_); + + swap(_impl_.storage_id_, other->_impl_.storage_id_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata FormatStorageResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[37]); } // =================================================================== -class RespondCaptureStatusResponse::_Internal { +class RespondFormatStorageRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondCaptureStatusResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondCaptureStatusResponse* msg); - static void set_has_camera_server_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::CameraServerResult& -RespondCaptureStatusResponse::_Internal::camera_server_result(const RespondCaptureStatusResponse* msg) { - return *msg->_impl_.camera_server_result_; -} -RespondCaptureStatusResponse::RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondFormatStorageRequest::RespondFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondFormatStorageRequest) } -RespondCaptureStatusResponse::RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondCaptureStatusResponse* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.camera_server_result_){nullptr}}; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); - } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +RespondFormatStorageRequest::RespondFormatStorageRequest(const RespondFormatStorageRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondFormatStorageRequest) } -inline void RespondCaptureStatusResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondFormatStorageRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} + decltype(_impl_.format_storage_feedback_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.camera_server_result_){nullptr} }; } -RespondCaptureStatusResponse::~RespondCaptureStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +RespondFormatStorageRequest::~RespondFormatStorageRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondFormatStorageRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4668,42 +7940,36 @@ RespondCaptureStatusResponse::~RespondCaptureStatusResponse() { SharedDtor(); } -inline void RespondCaptureStatusResponse::SharedDtor() { +inline void RespondFormatStorageRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void RespondCaptureStatusResponse::SetCachedSize(int size) const { +void RespondFormatStorageRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondCaptureStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +void RespondFormatStorageRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); - _impl_.camera_server_result_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.format_storage_feedback_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondCaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondFormatStorageRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); + _internal_set_format_storage_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); } else { goto handle_unusual; } @@ -4724,7 +7990,6 @@ const char* RespondCaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -4732,159 +7997,135 @@ const char* RespondCaptureStatusResponse::_InternalParse(const char* ptr, ::_pbi #undef CHK_ } -::uint8_t* RespondCaptureStatusResponse::_InternalSerialize( +::uint8_t* RespondFormatStorageRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(1, _Internal::camera_server_result(this), - _Internal::camera_server_result(this).GetCachedSize(), target, stream); + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + if (this->_internal_format_storage_feedback() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_format_storage_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondCaptureStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondFormatStorageRequest) return target; } -::size_t RespondCaptureStatusResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +::size_t RespondFormatStorageRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + if (this->_internal_format_storage_feedback() != 0) { total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.camera_server_result_); + ::_pbi::WireFormatLite::EnumSize(this->_internal_format_storage_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondCaptureStatusResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondFormatStorageRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondCaptureStatusResponse::MergeImpl + RespondFormatStorageRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondCaptureStatusResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondFormatStorageRequest::GetClassData() const { return &_class_data_; } -void RespondCaptureStatusResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondCaptureStatusResponse) +void RespondFormatStorageRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondFormatStorageRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( - from._internal_camera_server_result()); + if (from._internal_format_storage_feedback() != 0) { + _this->_internal_set_format_storage_feedback(from._internal_format_storage_feedback()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondCaptureStatusResponse::CopyFrom(const RespondCaptureStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) +void RespondFormatStorageRequest::CopyFrom(const RespondFormatStorageRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondCaptureStatusResponse::IsInitialized() const { +bool RespondFormatStorageRequest::IsInitialized() const { return true; } -void RespondCaptureStatusResponse::InternalSwap(RespondCaptureStatusResponse* other) { +void RespondFormatStorageRequest::InternalSwap(RespondFormatStorageRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); + swap(_impl_.format_storage_feedback_, other->_impl_.format_storage_feedback_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondFormatStorageRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[38]); } // =================================================================== -class SubscribeFormatStorageRequest::_Internal { +class RespondFormatStorageResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RespondFormatStorageResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondFormatStorageResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) -} -SubscribeFormatStorageRequest::SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from) - : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { - SubscribeFormatStorageRequest* const _this = this; (void)_this; - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) -} - - - - - -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeFormatStorageRequest::_class_data_ = { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, -}; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeFormatStorageRequest::GetClassData() const { return &_class_data_; } - - - - - - - -::PROTOBUF_NAMESPACE_ID::Metadata SubscribeFormatStorageRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); +const ::mavsdk::rpc::camera_server::CameraServerResult& +RespondFormatStorageResponse::_Internal::camera_server_result(const RespondFormatStorageResponse* msg) { + return *msg->_impl_.camera_server_result_; } -// =================================================================== - -class FormatStorageResponse::_Internal { - public: -}; - -FormatStorageResponse::FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondFormatStorageResponse::RespondFormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) } -FormatStorageResponse::FormatStorageResponse(const FormatStorageResponse& from) - : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( - from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.FormatStorageResponse) +RespondFormatStorageResponse::RespondFormatStorageResponse(const RespondFormatStorageResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + RespondFormatStorageResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) } -inline void FormatStorageResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondFormatStorageResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.storage_id_) { 0 } - + decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} }; } -FormatStorageResponse::~FormatStorageResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.FormatStorageResponse) +RespondFormatStorageResponse::~RespondFormatStorageResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondFormatStorageResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -4892,34 +8133,41 @@ FormatStorageResponse::~FormatStorageResponse() { SharedDtor(); } -inline void FormatStorageResponse::SharedDtor() { +inline void RespondFormatStorageResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void FormatStorageResponse::SetCachedSize(int size) const { +void RespondFormatStorageResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void FormatStorageResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.FormatStorageResponse) +void RespondFormatStorageResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.storage_id_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* FormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondFormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // int32 storage_id = 1; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; case 1: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { - _impl_.storage_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); CHK_(ptr); } else { goto handle_unusual; @@ -4941,6 +8189,7 @@ const char* FormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::Parse CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -4948,87 +8197,91 @@ const char* FormatStorageResponse::_InternalParse(const char* ptr, ::_pbi::Parse #undef CHK_ } -::uint8_t* FormatStorageResponse::_InternalSerialize( +::uint8_t* RespondFormatStorageResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.FormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 1, this->_internal_storage_id(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.FormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondFormatStorageResponse) return target; } -::size_t FormatStorageResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.FormatStorageResponse) +::size_t RespondFormatStorageResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_storage_id()); + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData FormatStorageResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondFormatStorageResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - FormatStorageResponse::MergeImpl + RespondFormatStorageResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*FormatStorageResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondFormatStorageResponse::GetClassData() const { return &_class_data_; } -void FormatStorageResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.FormatStorageResponse) +void RespondFormatStorageResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondFormatStorageResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_storage_id() != 0) { - _this->_internal_set_storage_id(from._internal_storage_id()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void FormatStorageResponse::CopyFrom(const FormatStorageResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.FormatStorageResponse) +void RespondFormatStorageResponse::CopyFrom(const RespondFormatStorageResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondFormatStorageResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool FormatStorageResponse::IsInitialized() const { +bool RespondFormatStorageResponse::IsInitialized() const { return true; } -void FormatStorageResponse::InternalSwap(FormatStorageResponse* other) { +void RespondFormatStorageResponse::InternalSwap(RespondFormatStorageResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - - swap(_impl_.storage_id_, other->_impl_.storage_id_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata FormatStorageResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondFormatStorageResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[39]); } // =================================================================== @@ -5066,7 +8319,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeResetSettingsRequest: ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeResetSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[40]); } // =================================================================== @@ -5240,61 +8493,37 @@ void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ResetSettingsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[41]); } // =================================================================== -class RespondTakePhotoRequest::_Internal { +class RespondResetSettingsRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info(const RespondTakePhotoRequest* msg); - static void set_has_capture_info(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera_server::CaptureInfo& -RespondTakePhotoRequest::_Internal::capture_info(const RespondTakePhotoRequest* msg) { - return *msg->_impl_.capture_info_; -} -RespondTakePhotoRequest::RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondResetSettingsRequest::RespondResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) } -RespondTakePhotoRequest::RespondTakePhotoRequest(const RespondTakePhotoRequest& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondTakePhotoRequest* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){from._impl_._has_bits_} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_info_){nullptr} - , decltype(_impl_.take_photo_feedback_) {} - }; - - _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_impl_.capture_info_ = new ::mavsdk::rpc::camera_server::CaptureInfo(*from._impl_.capture_info_); - } - _this->_impl_.take_photo_feedback_ = from._impl_.take_photo_feedback_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +RespondResetSettingsRequest::RespondResetSettingsRequest(const RespondResetSettingsRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message(), _impl_(from._impl_) { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>( + from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) } -inline void RespondTakePhotoRequest::SharedCtor(::_pb::Arena* arena) { +inline void RespondResetSettingsRequest::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_._has_bits_){} - , /*decltype(_impl_._cached_size_)*/{} - , decltype(_impl_.capture_info_){nullptr} - , decltype(_impl_.take_photo_feedback_) { 0 } + decltype(_impl_.reset_settings_feedback_) { 0 } + , /*decltype(_impl_._cached_size_)*/{} }; } -RespondTakePhotoRequest::~RespondTakePhotoRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +RespondResetSettingsRequest::~RespondResetSettingsRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsRequest) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -5302,53 +8531,36 @@ RespondTakePhotoRequest::~RespondTakePhotoRequest() { SharedDtor(); } -inline void RespondTakePhotoRequest::SharedDtor() { +inline void RespondResetSettingsRequest::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - if (this != internal_default_instance()) delete _impl_.capture_info_; } -void RespondTakePhotoRequest::SetCachedSize(int size) const { +void RespondResetSettingsRequest::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondTakePhotoRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +void RespondResetSettingsRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.capture_info_ != nullptr); - _impl_.capture_info_->Clear(); - } - _impl_.take_photo_feedback_ = 0; - _impl_._has_bits_.Clear(); + _impl_.reset_settings_feedback_ = 0; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondResetSettingsRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure - _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { ::int32_t val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); - _internal_set_take_photo_feedback(static_cast<::mavsdk::rpc::camera_server::TakePhotoFeedback>(val)); - } else { - goto handle_unusual; - } - continue; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { - ptr = ctx->ParseMessage(_internal_mutable_capture_info(), ptr); - CHK_(ptr); + _internal_set_reset_settings_feedback(static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(val)); } else { goto handle_unusual; } @@ -5369,7 +8581,6 @@ const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::Par CHK_(ptr != nullptr); } // while message_done: - _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -5377,138 +8588,112 @@ const char* RespondTakePhotoRequest::_InternalParse(const char* ptr, ::_pbi::Par #undef CHK_ } -::uint8_t* RespondTakePhotoRequest::_InternalSerialize( +::uint8_t* RespondResetSettingsRequest::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - if (this->_internal_take_photo_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + if (this->_internal_reset_settings_feedback() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_take_photo_feedback(), target); - } - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - if (cached_has_bits & 0x00000001u) { - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: - InternalWriteMessage(2, _Internal::capture_info(this), - _Internal::capture_info(this).GetCachedSize(), target, stream); + 1, this->_internal_reset_settings_feedback(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::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.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondResetSettingsRequest) return target; } -::size_t RespondTakePhotoRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +::size_t RespondResetSettingsRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( - *_impl_.capture_info_); - } - - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - if (this->_internal_take_photo_feedback() != 0) { + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + if (this->_internal_reset_settings_feedback() != 0) { total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_take_photo_feedback()); + ::_pbi::WireFormatLite::EnumSize(this->_internal_reset_settings_feedback()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoRequest::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondResetSettingsRequest::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondTakePhotoRequest::MergeImpl + RespondResetSettingsRequest::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoRequest::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondResetSettingsRequest::GetClassData() const { return &_class_data_; } -void RespondTakePhotoRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoRequest) +void RespondResetSettingsRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondResetSettingsRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_capture_info()->::mavsdk::rpc::camera_server::CaptureInfo::MergeFrom( - from._internal_capture_info()); - } - if (from._internal_take_photo_feedback() != 0) { - _this->_internal_set_take_photo_feedback(from._internal_take_photo_feedback()); + if (from._internal_reset_settings_feedback() != 0) { + _this->_internal_set_reset_settings_feedback(from._internal_reset_settings_feedback()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondTakePhotoRequest::CopyFrom(const RespondTakePhotoRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoRequest) +void RespondResetSettingsRequest::CopyFrom(const RespondResetSettingsRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondTakePhotoRequest::IsInitialized() const { +bool RespondResetSettingsRequest::IsInitialized() const { return true; } -void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { +void RespondResetSettingsRequest::InternalSwap(RespondResetSettingsRequest* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.take_photo_feedback_) - + sizeof(RespondTakePhotoRequest::_impl_.take_photo_feedback_) - - PROTOBUF_FIELD_OFFSET(RespondTakePhotoRequest, _impl_.capture_info_)>( - reinterpret_cast(&_impl_.capture_info_), - reinterpret_cast(&other->_impl_.capture_info_)); + swap(_impl_.reset_settings_feedback_, other->_impl_.reset_settings_feedback_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondResetSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[42]); } // =================================================================== -class RespondTakePhotoResponse::_Internal { +class RespondResetSettingsResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RespondTakePhotoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondTakePhotoResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(RespondResetSettingsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const RespondResetSettingsResponse* msg); static void set_has_camera_server_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; const ::mavsdk::rpc::camera_server::CameraServerResult& -RespondTakePhotoResponse::_Internal::camera_server_result(const RespondTakePhotoResponse* msg) { +RespondResetSettingsResponse::_Internal::camera_server_result(const RespondResetSettingsResponse* msg) { return *msg->_impl_.camera_server_result_; } -RespondTakePhotoResponse::RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) +RespondResetSettingsResponse::RespondResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) } -RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoResponse& from) +RespondResetSettingsResponse::RespondResetSettingsResponse(const RespondResetSettingsResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - RespondTakePhotoResponse* const _this = this; (void)_this; + RespondResetSettingsResponse* const _this = this; (void)_this; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){from._impl_._has_bits_} , /*decltype(_impl_._cached_size_)*/{} @@ -5518,10 +8703,10 @@ RespondTakePhotoResponse::RespondTakePhotoResponse(const RespondTakePhotoRespons if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) } -inline void RespondTakePhotoResponse::SharedCtor(::_pb::Arena* arena) { +inline void RespondResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ decltype(_impl_._has_bits_){} @@ -5530,8 +8715,8 @@ inline void RespondTakePhotoResponse::SharedCtor(::_pb::Arena* arena) { }; } -RespondTakePhotoResponse::~RespondTakePhotoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +RespondResetSettingsResponse::~RespondResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.RespondResetSettingsResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -5539,17 +8724,17 @@ RespondTakePhotoResponse::~RespondTakePhotoResponse() { SharedDtor(); } -inline void RespondTakePhotoResponse::SharedDtor() { +inline void RespondResetSettingsResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); if (this != internal_default_instance()) delete _impl_.camera_server_result_; } -void RespondTakePhotoResponse::SetCachedSize(int size) const { +void RespondResetSettingsResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void RespondTakePhotoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +void RespondResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -5563,7 +8748,7 @@ void RespondTakePhotoResponse::Clear() { _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* RespondResetSettingsResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { @@ -5603,9 +8788,9 @@ const char* RespondTakePhotoResponse::_InternalParse(const char* ptr, ::_pbi::Pa #undef CHK_ } -::uint8_t* RespondTakePhotoResponse::_InternalSerialize( +::uint8_t* RespondResetSettingsResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -5621,12 +8806,12 @@ ::uint8_t* RespondTakePhotoResponse::_InternalSerialize( target = ::_pbi::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.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera_server.RespondResetSettingsResponse) return target; } -::size_t RespondTakePhotoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +::size_t RespondResetSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -5644,17 +8829,17 @@ ::size_t RespondTakePhotoResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondTakePhotoResponse::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData RespondResetSettingsResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - RespondTakePhotoResponse::MergeImpl + RespondResetSettingsResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondTakePhotoResponse::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*RespondResetSettingsResponse::GetClassData() const { return &_class_data_; } -void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondTakePhotoResponse) +void RespondResetSettingsResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.RespondResetSettingsResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -5666,28 +8851,28 @@ void RespondTakePhotoResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_ms _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void RespondTakePhotoResponse::CopyFrom(const RespondTakePhotoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondTakePhotoResponse) +void RespondResetSettingsResponse::CopyFrom(const RespondResetSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.RespondResetSettingsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool RespondTakePhotoResponse::IsInitialized() const { +bool RespondResetSettingsResponse::IsInitialized() const { return true; } -void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { +void RespondResetSettingsResponse::InternalSwap(RespondResetSettingsResponse* other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); } -::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata RespondResetSettingsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[43]); } // =================================================================== @@ -6272,7 +9457,7 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[44]); } // =================================================================== @@ -6577,7 +9762,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[45]); } // =================================================================== @@ -6882,7 +10067,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[46]); } // =================================================================== @@ -7285,7 +10470,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[47]); } // =================================================================== @@ -7514,7 +10699,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[34]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[48]); } // =================================================================== @@ -7940,7 +11125,7 @@ void StorageInformation::InternalSwap(StorageInformation* other) { ::PROTOBUF_NAMESPACE_ID::Metadata StorageInformation::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[35]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[49]); } // =================================================================== @@ -8290,7 +11475,7 @@ void CaptureStatus::InternalSwap(CaptureStatus* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[36]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[50]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -8321,6 +11506,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::TakePhotoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::TakePhotoResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest >(arena); @@ -8329,6 +11522,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StartVideoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StartVideoResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStartVideoRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStartVideoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStartVideoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStartVideoResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStartVideoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStartVideoResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest >(arena); @@ -8337,6 +11538,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStopVideoRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStopVideoRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStopVideoRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStopVideoResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStopVideoResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStopVideoResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest >(arena); @@ -8345,6 +11554,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StartVideoStreamingRe Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest >(arena); @@ -8353,6 +11570,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::StopVideoStreamingRes Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest >(arena); @@ -8361,6 +11586,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetModeResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetModeResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetModeResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondSetModeRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondSetModeRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondSetModeRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondSetModeResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondSetModeResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondSetModeResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest >(arena); @@ -8401,6 +11634,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::FormatStorageResponse Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::FormatStorageResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::FormatStorageResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest >(arena); @@ -8409,13 +11650,13 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::ResetSettingsResponse Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::ResetSettingsResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::ResetSettingsResponse >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest >(arena); +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest >(arena); } -template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* -Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(Arena* arena) { - return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse >(arena); +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse >(arena); } template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Information >(Arena* arena) { diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 914991c3d6..f3b7003115 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -89,6 +89,48 @@ extern RespondCaptureStatusRequestDefaultTypeInternal _RespondCaptureStatusReque class RespondCaptureStatusResponse; struct RespondCaptureStatusResponseDefaultTypeInternal; extern RespondCaptureStatusResponseDefaultTypeInternal _RespondCaptureStatusResponse_default_instance_; +class RespondFormatStorageRequest; +struct RespondFormatStorageRequestDefaultTypeInternal; +extern RespondFormatStorageRequestDefaultTypeInternal _RespondFormatStorageRequest_default_instance_; +class RespondFormatStorageResponse; +struct RespondFormatStorageResponseDefaultTypeInternal; +extern RespondFormatStorageResponseDefaultTypeInternal _RespondFormatStorageResponse_default_instance_; +class RespondResetSettingsRequest; +struct RespondResetSettingsRequestDefaultTypeInternal; +extern RespondResetSettingsRequestDefaultTypeInternal _RespondResetSettingsRequest_default_instance_; +class RespondResetSettingsResponse; +struct RespondResetSettingsResponseDefaultTypeInternal; +extern RespondResetSettingsResponseDefaultTypeInternal _RespondResetSettingsResponse_default_instance_; +class RespondSetModeRequest; +struct RespondSetModeRequestDefaultTypeInternal; +extern RespondSetModeRequestDefaultTypeInternal _RespondSetModeRequest_default_instance_; +class RespondSetModeResponse; +struct RespondSetModeResponseDefaultTypeInternal; +extern RespondSetModeResponseDefaultTypeInternal _RespondSetModeResponse_default_instance_; +class RespondStartVideoRequest; +struct RespondStartVideoRequestDefaultTypeInternal; +extern RespondStartVideoRequestDefaultTypeInternal _RespondStartVideoRequest_default_instance_; +class RespondStartVideoResponse; +struct RespondStartVideoResponseDefaultTypeInternal; +extern RespondStartVideoResponseDefaultTypeInternal _RespondStartVideoResponse_default_instance_; +class RespondStartVideoStreamingRequest; +struct RespondStartVideoStreamingRequestDefaultTypeInternal; +extern RespondStartVideoStreamingRequestDefaultTypeInternal _RespondStartVideoStreamingRequest_default_instance_; +class RespondStartVideoStreamingResponse; +struct RespondStartVideoStreamingResponseDefaultTypeInternal; +extern RespondStartVideoStreamingResponseDefaultTypeInternal _RespondStartVideoStreamingResponse_default_instance_; +class RespondStopVideoRequest; +struct RespondStopVideoRequestDefaultTypeInternal; +extern RespondStopVideoRequestDefaultTypeInternal _RespondStopVideoRequest_default_instance_; +class RespondStopVideoResponse; +struct RespondStopVideoResponseDefaultTypeInternal; +extern RespondStopVideoResponseDefaultTypeInternal _RespondStopVideoResponse_default_instance_; +class RespondStopVideoStreamingRequest; +struct RespondStopVideoStreamingRequestDefaultTypeInternal; +extern RespondStopVideoStreamingRequestDefaultTypeInternal _RespondStopVideoStreamingRequest_default_instance_; +class RespondStopVideoStreamingResponse; +struct RespondStopVideoStreamingResponseDefaultTypeInternal; +extern RespondStopVideoStreamingResponseDefaultTypeInternal _RespondStopVideoStreamingResponse_default_instance_; class RespondStorageInformationRequest; struct RespondStorageInformationRequestDefaultTypeInternal; extern RespondStorageInformationRequestDefaultTypeInternal _RespondStorageInformationRequest_default_instance_; @@ -194,6 +236,34 @@ ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* Arena::CreateMaybeMes template <> ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::RespondFormatStorageRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondFormatStorageRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondFormatStorageResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondFormatStorageResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondResetSettingsRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondResetSettingsRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondResetSettingsResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondResetSettingsResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondSetModeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondSetModeRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondSetModeResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondSetModeResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStartVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStartVideoRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStartVideoResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStopVideoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStopVideoRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStopVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStopVideoResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStorageInformationRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::RespondStorageInformationResponse>(Arena*); @@ -419,39 +489,39 @@ inline bool CaptureStatus_VideoStatus_Parse(absl::string_view name, CaptureStatu return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( CaptureStatus_VideoStatus_descriptor(), name, value); } -enum TakePhotoFeedback : int { - TAKE_PHOTO_FEEDBACK_UNKNOWN = 0, - TAKE_PHOTO_FEEDBACK_OK = 1, - TAKE_PHOTO_FEEDBACK_BUSY = 2, - TAKE_PHOTO_FEEDBACK_FAILED = 3, - TakePhotoFeedback_INT_MIN_SENTINEL_DO_NOT_USE_ = +enum CameraFeedback : int { + CAMERA_FEEDBACK_UNKNOWN = 0, + CAMERA_FEEDBACK_OK = 1, + CAMERA_FEEDBACK_BUSY = 2, + CAMERA_FEEDBACK_FAILED = 3, + CameraFeedback_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::int32_t>::min(), - TakePhotoFeedback_INT_MAX_SENTINEL_DO_NOT_USE_ = + CameraFeedback_INT_MAX_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::int32_t>::max(), }; -bool TakePhotoFeedback_IsValid(int value); -constexpr TakePhotoFeedback TakePhotoFeedback_MIN = static_cast(0); -constexpr TakePhotoFeedback TakePhotoFeedback_MAX = static_cast(3); -constexpr int TakePhotoFeedback_ARRAYSIZE = 3 + 1; +bool CameraFeedback_IsValid(int value); +constexpr CameraFeedback CameraFeedback_MIN = static_cast(0); +constexpr CameraFeedback CameraFeedback_MAX = static_cast(3); +constexpr int CameraFeedback_ARRAYSIZE = 3 + 1; const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* -TakePhotoFeedback_descriptor(); +CameraFeedback_descriptor(); template -const std::string& TakePhotoFeedback_Name(T value) { - static_assert(std::is_same::value || +const std::string& CameraFeedback_Name(T value) { + static_assert(std::is_same::value || std::is_integral::value, - "Incorrect type passed to TakePhotoFeedback_Name()."); - return TakePhotoFeedback_Name(static_cast(value)); + "Incorrect type passed to CameraFeedback_Name()."); + return CameraFeedback_Name(static_cast(value)); } template <> -inline const std::string& TakePhotoFeedback_Name(TakePhotoFeedback value) { - return ::PROTOBUF_NAMESPACE_ID::internal::NameOfDenseEnum( static_cast(value)); } -inline bool TakePhotoFeedback_Parse(absl::string_view name, TakePhotoFeedback* value) { - return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( - TakePhotoFeedback_descriptor(), name, value); +inline bool CameraFeedback_Parse(absl::string_view name, CameraFeedback* value) { + return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( + CameraFeedback_descriptor(), name, value); } enum Mode : int { MODE_UNKNOWN = 0, @@ -1406,24 +1476,25 @@ class TakePhotoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStartVideoRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { +class RespondTakePhotoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { public: - inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} + inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} + ~RespondTakePhotoRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from); - SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept - : SubscribeStartVideoRequest() { + RespondTakePhotoRequest(const RespondTakePhotoRequest& from); + RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept + : RespondTakePhotoRequest() { *this = ::std::move(from); } - inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { + inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& from) noexcept { + inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1453,20 +1524,20 @@ class SubscribeStartVideoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStartVideoRequest& default_instance() { + static const RespondTakePhotoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStartVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStartVideoRequest_default_instance_); + static inline const RespondTakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 6; - friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { + friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStartVideoRequest* other) { + inline void Swap(RespondTakePhotoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -1479,7 +1550,7 @@ class SubscribeStartVideoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStartVideoRequest* other) { + void UnsafeArenaSwap(RespondTakePhotoRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1487,26 +1558,40 @@ class SubscribeStartVideoRequest final : // implements Message ---------------------------------------------- - SubscribeStartVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStartVideoRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStartVideoRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondTakePhotoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondTakePhotoRequest& from) { + RespondTakePhotoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondTakePhotoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStartVideoRequest"; + return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; } protected: - explicit SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -1518,7 +1603,35 @@ class SubscribeStartVideoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) + enum : int { + kCaptureInfoFieldNumber = 2, + kTakePhotoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; + bool has_capture_info() const; + void clear_capture_info() ; + const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); + ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); + void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + private: + const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; + ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); + public: + void unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); + ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); + // .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; + void clear_take_photo_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback take_photo_feedback() const; + void set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_take_photo_feedback() const; + void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) private: class _Internal; @@ -1526,29 +1639,34 @@ class SubscribeStartVideoRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; + int take_photo_feedback_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StartVideoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { +class RespondTakePhotoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { public: - inline StartVideoResponse() : StartVideoResponse(nullptr) {} - ~StartVideoResponse() override; + inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} + ~RespondTakePhotoResponse() override; template - explicit PROTOBUF_CONSTEXPR StartVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StartVideoResponse(const StartVideoResponse& from); - StartVideoResponse(StartVideoResponse&& from) noexcept - : StartVideoResponse() { + RespondTakePhotoResponse(const RespondTakePhotoResponse& from); + RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept + : RespondTakePhotoResponse() { *this = ::std::move(from); } - inline StartVideoResponse& operator=(const StartVideoResponse& from) { + inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { CopyFrom(from); return *this; } - inline StartVideoResponse& operator=(StartVideoResponse&& from) noexcept { + inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1578,20 +1696,20 @@ class StartVideoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoResponse& default_instance() { + static const RespondTakePhotoResponse& default_instance() { return *internal_default_instance(); } - static inline const StartVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StartVideoResponse_default_instance_); + static inline const RespondTakePhotoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 7; - friend void swap(StartVideoResponse& a, StartVideoResponse& b) { + friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); } - inline void Swap(StartVideoResponse* other) { + inline void Swap(RespondTakePhotoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -1604,7 +1722,7 @@ class StartVideoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoResponse* other) { + void UnsafeArenaSwap(RespondTakePhotoResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1612,14 +1730,14 @@ class StartVideoResponse final : // implements Message ---------------------------------------------- - StartVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StartVideoResponse& from); + void CopyFrom(const RespondTakePhotoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StartVideoResponse& from) { - StartVideoResponse::MergeImpl(*this, from); + void MergeFrom( const RespondTakePhotoResponse& from) { + RespondTakePhotoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -1637,15 +1755,15 @@ class StartVideoResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StartVideoResponse* other); + void InternalSwap(RespondTakePhotoResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StartVideoResponse"; + return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; } protected: - explicit StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -1658,19 +1776,23 @@ class StartVideoResponse final : // accessors ------------------------------------------------------- enum : int { - kStreamIdFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) private: class _Internal; @@ -1678,31 +1800,32 @@ class StartVideoResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t stream_id_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStopVideoRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { +class SubscribeStartVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) */ { public: - inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} + inline SubscribeStartVideoRequest() : SubscribeStartVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from); - SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept - : SubscribeStopVideoRequest() { + SubscribeStartVideoRequest(const SubscribeStartVideoRequest& from); + SubscribeStartVideoRequest(SubscribeStartVideoRequest&& from) noexcept + : SubscribeStartVideoRequest() { *this = ::std::move(from); } - inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { + inline SubscribeStartVideoRequest& operator=(const SubscribeStartVideoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& from) noexcept { + inline SubscribeStartVideoRequest& operator=(SubscribeStartVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1732,20 +1855,20 @@ class SubscribeStopVideoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStopVideoRequest& default_instance() { + static const SubscribeStartVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStopVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStopVideoRequest_default_instance_); + static inline const SubscribeStartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 8; - friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { + friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStopVideoRequest* other) { + inline void Swap(SubscribeStartVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -1758,7 +1881,7 @@ class SubscribeStopVideoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStopVideoRequest* other) { + void UnsafeArenaSwap(SubscribeStartVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1766,15 +1889,15 @@ class SubscribeStopVideoRequest final : // implements Message ---------------------------------------------- - SubscribeStopVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStartVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStopVideoRequest& from) { + inline void CopyFrom(const SubscribeStartVideoRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStopVideoRequest& from) { + void MergeFrom(const SubscribeStartVideoRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1782,10 +1905,10 @@ class SubscribeStopVideoRequest final : private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStopVideoRequest"; + return "mavsdk.rpc.camera_server.SubscribeStartVideoRequest"; } protected: - explicit SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -1797,7 +1920,7 @@ class SubscribeStopVideoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoRequest) private: class _Internal; @@ -1809,25 +1932,25 @@ class SubscribeStopVideoRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StopVideoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { +class StartVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoResponse) */ { public: - inline StopVideoResponse() : StopVideoResponse(nullptr) {} - ~StopVideoResponse() override; + inline StartVideoResponse() : StartVideoResponse(nullptr) {} + ~StartVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR StopVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StopVideoResponse(const StopVideoResponse& from); - StopVideoResponse(StopVideoResponse&& from) noexcept - : StopVideoResponse() { + StartVideoResponse(const StartVideoResponse& from); + StartVideoResponse(StartVideoResponse&& from) noexcept + : StartVideoResponse() { *this = ::std::move(from); } - inline StopVideoResponse& operator=(const StopVideoResponse& from) { + inline StartVideoResponse& operator=(const StartVideoResponse& from) { CopyFrom(from); return *this; } - inline StopVideoResponse& operator=(StopVideoResponse&& from) noexcept { + inline StartVideoResponse& operator=(StartVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1857,20 +1980,20 @@ class StopVideoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoResponse& default_instance() { + static const StartVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const StopVideoResponse* internal_default_instance() { - return reinterpret_cast( - &_StopVideoResponse_default_instance_); + static inline const StartVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 9; - friend void swap(StopVideoResponse& a, StopVideoResponse& b) { + friend void swap(StartVideoResponse& a, StartVideoResponse& b) { a.Swap(&b); } - inline void Swap(StopVideoResponse* other) { + inline void Swap(StartVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -1883,7 +2006,7 @@ class StopVideoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoResponse* other) { + void UnsafeArenaSwap(StartVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -1891,14 +2014,14 @@ class StopVideoResponse final : // implements Message ---------------------------------------------- - StopVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StartVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StopVideoResponse& from); + void CopyFrom(const StartVideoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StopVideoResponse& from) { - StopVideoResponse::MergeImpl(*this, from); + void MergeFrom( const StartVideoResponse& from) { + StartVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -1916,15 +2039,15 @@ class StopVideoResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StopVideoResponse* other); + void InternalSwap(StartVideoResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StopVideoResponse"; + return "mavsdk.rpc.camera_server.StartVideoResponse"; } protected: - explicit StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -1949,7 +2072,7 @@ class StopVideoResponse final : void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoResponse) private: class _Internal; @@ -1964,24 +2087,25 @@ class StopVideoResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStartVideoStreamingRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) */ { +class RespondStartVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoRequest) */ { public: - inline SubscribeStartVideoStreamingRequest() : SubscribeStartVideoStreamingRequest(nullptr) {} + inline RespondStartVideoRequest() : RespondStartVideoRequest(nullptr) {} + ~RespondStartVideoRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from); - SubscribeStartVideoStreamingRequest(SubscribeStartVideoStreamingRequest&& from) noexcept - : SubscribeStartVideoStreamingRequest() { + RespondStartVideoRequest(const RespondStartVideoRequest& from); + RespondStartVideoRequest(RespondStartVideoRequest&& from) noexcept + : RespondStartVideoRequest() { *this = ::std::move(from); } - inline SubscribeStartVideoStreamingRequest& operator=(const SubscribeStartVideoStreamingRequest& from) { + inline RespondStartVideoRequest& operator=(const RespondStartVideoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStartVideoStreamingRequest& operator=(SubscribeStartVideoStreamingRequest&& from) noexcept { + inline RespondStartVideoRequest& operator=(RespondStartVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2011,20 +2135,20 @@ class SubscribeStartVideoStreamingRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStartVideoStreamingRequest& default_instance() { + static const RespondStartVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStartVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStartVideoStreamingRequest_default_instance_); + static inline const RespondStartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 10; - friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { + friend void swap(RespondStartVideoRequest& a, RespondStartVideoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStartVideoStreamingRequest* other) { + inline void Swap(RespondStartVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2037,7 +2161,7 @@ class SubscribeStartVideoStreamingRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStartVideoStreamingRequest* other) { + void UnsafeArenaSwap(RespondStartVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2045,26 +2169,40 @@ class SubscribeStartVideoStreamingRequest final : // implements Message ---------------------------------------------- - SubscribeStartVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStartVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + RespondStartVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStartVideoStreamingRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondStartVideoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondStartVideoRequest& from) { + RespondStartVideoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondStartVideoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.RespondStartVideoRequest"; } protected: - explicit SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStartVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2076,7 +2214,20 @@ class SubscribeStartVideoStreamingRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) + enum : int { + kStartVideoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; + void clear_start_video_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback start_video_feedback() const; + void set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_feedback() const; + void _internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoRequest) private: class _Internal; @@ -2084,29 +2235,32 @@ class SubscribeStartVideoStreamingRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + int start_video_feedback_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StartVideoStreamingResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoStreamingResponse) */ { +class RespondStartVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoResponse) */ { public: - inline StartVideoStreamingResponse() : StartVideoStreamingResponse(nullptr) {} - ~StartVideoStreamingResponse() override; + inline RespondStartVideoResponse() : RespondStartVideoResponse(nullptr) {} + ~RespondStartVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StartVideoStreamingResponse(const StartVideoStreamingResponse& from); - StartVideoStreamingResponse(StartVideoStreamingResponse&& from) noexcept - : StartVideoStreamingResponse() { + RespondStartVideoResponse(const RespondStartVideoResponse& from); + RespondStartVideoResponse(RespondStartVideoResponse&& from) noexcept + : RespondStartVideoResponse() { *this = ::std::move(from); } - inline StartVideoStreamingResponse& operator=(const StartVideoStreamingResponse& from) { + inline RespondStartVideoResponse& operator=(const RespondStartVideoResponse& from) { CopyFrom(from); return *this; } - inline StartVideoStreamingResponse& operator=(StartVideoStreamingResponse&& from) noexcept { + inline RespondStartVideoResponse& operator=(RespondStartVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2136,20 +2290,20 @@ class StartVideoStreamingResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoStreamingResponse& default_instance() { + static const RespondStartVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const StartVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_StartVideoStreamingResponse_default_instance_); + static inline const RespondStartVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 11; - friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { + friend void swap(RespondStartVideoResponse& a, RespondStartVideoResponse& b) { a.Swap(&b); } - inline void Swap(StartVideoStreamingResponse* other) { + inline void Swap(RespondStartVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2162,7 +2316,7 @@ class StartVideoStreamingResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoStreamingResponse* other) { + void UnsafeArenaSwap(RespondStartVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2170,14 +2324,14 @@ class StartVideoStreamingResponse final : // implements Message ---------------------------------------------- - StartVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStartVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StartVideoStreamingResponse& from); + void CopyFrom(const RespondStartVideoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StartVideoStreamingResponse& from) { - StartVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStartVideoResponse& from) { + RespondStartVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -2195,15 +2349,15 @@ class StartVideoStreamingResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StartVideoStreamingResponse* other); + void InternalSwap(RespondStartVideoResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StartVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.RespondStartVideoResponse"; } protected: - explicit StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStartVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2216,19 +2370,23 @@ class StartVideoStreamingResponse final : // accessors ------------------------------------------------------- enum : int { - kStreamIdFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoStreamingResponse) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoResponse) private: class _Internal; @@ -2236,31 +2394,32 @@ class StartVideoStreamingResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t stream_id_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStopVideoStreamingRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) */ { +class SubscribeStopVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) */ { public: - inline SubscribeStopVideoStreamingRequest() : SubscribeStopVideoStreamingRequest(nullptr) {} + inline SubscribeStopVideoRequest() : SubscribeStopVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from); - SubscribeStopVideoStreamingRequest(SubscribeStopVideoStreamingRequest&& from) noexcept - : SubscribeStopVideoStreamingRequest() { + SubscribeStopVideoRequest(const SubscribeStopVideoRequest& from); + SubscribeStopVideoRequest(SubscribeStopVideoRequest&& from) noexcept + : SubscribeStopVideoRequest() { *this = ::std::move(from); } - inline SubscribeStopVideoStreamingRequest& operator=(const SubscribeStopVideoStreamingRequest& from) { + inline SubscribeStopVideoRequest& operator=(const SubscribeStopVideoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStopVideoStreamingRequest& operator=(SubscribeStopVideoStreamingRequest&& from) noexcept { + inline SubscribeStopVideoRequest& operator=(SubscribeStopVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2290,20 +2449,20 @@ class SubscribeStopVideoStreamingRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStopVideoStreamingRequest& default_instance() { + static const SubscribeStopVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStopVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStopVideoStreamingRequest_default_instance_); + static inline const SubscribeStopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 12; - friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { + friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStopVideoStreamingRequest* other) { + inline void Swap(SubscribeStopVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2316,7 +2475,7 @@ class SubscribeStopVideoStreamingRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStopVideoStreamingRequest* other) { + void UnsafeArenaSwap(SubscribeStopVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2324,15 +2483,15 @@ class SubscribeStopVideoStreamingRequest final : // implements Message ---------------------------------------------- - SubscribeStopVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStopVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStopVideoStreamingRequest& from) { + inline void CopyFrom(const SubscribeStopVideoRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStopVideoStreamingRequest& from) { + void MergeFrom(const SubscribeStopVideoRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2340,10 +2499,10 @@ class SubscribeStopVideoStreamingRequest final : private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest"; + return "mavsdk.rpc.camera_server.SubscribeStopVideoRequest"; } protected: - explicit SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2355,7 +2514,7 @@ class SubscribeStopVideoStreamingRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoRequest) private: class _Internal; @@ -2367,25 +2526,25 @@ class SubscribeStopVideoStreamingRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StopVideoStreamingResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoStreamingResponse) */ { +class StopVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoResponse) */ { public: - inline StopVideoStreamingResponse() : StopVideoStreamingResponse(nullptr) {} - ~StopVideoStreamingResponse() override; + inline StopVideoResponse() : StopVideoResponse(nullptr) {} + ~StopVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StopVideoStreamingResponse(const StopVideoStreamingResponse& from); - StopVideoStreamingResponse(StopVideoStreamingResponse&& from) noexcept - : StopVideoStreamingResponse() { + StopVideoResponse(const StopVideoResponse& from); + StopVideoResponse(StopVideoResponse&& from) noexcept + : StopVideoResponse() { *this = ::std::move(from); } - inline StopVideoStreamingResponse& operator=(const StopVideoStreamingResponse& from) { + inline StopVideoResponse& operator=(const StopVideoResponse& from) { CopyFrom(from); return *this; } - inline StopVideoStreamingResponse& operator=(StopVideoStreamingResponse&& from) noexcept { + inline StopVideoResponse& operator=(StopVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2415,20 +2574,20 @@ class StopVideoStreamingResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoStreamingResponse& default_instance() { + static const StopVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const StopVideoStreamingResponse* internal_default_instance() { - return reinterpret_cast( - &_StopVideoStreamingResponse_default_instance_); + static inline const StopVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 13; - friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { + friend void swap(StopVideoResponse& a, StopVideoResponse& b) { a.Swap(&b); } - inline void Swap(StopVideoStreamingResponse* other) { + inline void Swap(StopVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2441,7 +2600,7 @@ class StopVideoStreamingResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoStreamingResponse* other) { + void UnsafeArenaSwap(StopVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2449,14 +2608,14 @@ class StopVideoStreamingResponse final : // implements Message ---------------------------------------------- - StopVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StopVideoStreamingResponse& from); + void CopyFrom(const StopVideoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StopVideoStreamingResponse& from) { - StopVideoStreamingResponse::MergeImpl(*this, from); + void MergeFrom( const StopVideoResponse& from) { + StopVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -2474,15 +2633,15 @@ class StopVideoStreamingResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StopVideoStreamingResponse* other); + void InternalSwap(StopVideoResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StopVideoStreamingResponse"; + return "mavsdk.rpc.camera_server.StopVideoResponse"; } protected: - explicit StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2507,7 +2666,7 @@ class StopVideoStreamingResponse final : void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoStreamingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoResponse) private: class _Internal; @@ -2522,24 +2681,25 @@ class StopVideoStreamingResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeSetModeRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeSetModeRequest) */ { +class RespondStopVideoRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoRequest) */ { public: - inline SubscribeSetModeRequest() : SubscribeSetModeRequest(nullptr) {} + inline RespondStopVideoRequest() : RespondStopVideoRequest(nullptr) {} + ~RespondStopVideoRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeSetModeRequest(const SubscribeSetModeRequest& from); - SubscribeSetModeRequest(SubscribeSetModeRequest&& from) noexcept - : SubscribeSetModeRequest() { + RespondStopVideoRequest(const RespondStopVideoRequest& from); + RespondStopVideoRequest(RespondStopVideoRequest&& from) noexcept + : RespondStopVideoRequest() { *this = ::std::move(from); } - inline SubscribeSetModeRequest& operator=(const SubscribeSetModeRequest& from) { + inline RespondStopVideoRequest& operator=(const RespondStopVideoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeSetModeRequest& operator=(SubscribeSetModeRequest&& from) noexcept { + inline RespondStopVideoRequest& operator=(RespondStopVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2569,20 +2729,20 @@ class SubscribeSetModeRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeSetModeRequest& default_instance() { + static const RespondStopVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeSetModeRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeSetModeRequest_default_instance_); + static inline const RespondStopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = 14; - friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { + friend void swap(RespondStopVideoRequest& a, RespondStopVideoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeSetModeRequest* other) { + inline void Swap(RespondStopVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2595,7 +2755,7 @@ class SubscribeSetModeRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeSetModeRequest* other) { + void UnsafeArenaSwap(RespondStopVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2603,26 +2763,40 @@ class SubscribeSetModeRequest final : // implements Message ---------------------------------------------- - SubscribeSetModeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeSetModeRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + RespondStopVideoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeSetModeRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondStopVideoRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondStopVideoRequest& from) { + RespondStopVideoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondStopVideoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeSetModeRequest"; + return "mavsdk.rpc.camera_server.RespondStopVideoRequest"; } protected: - explicit SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStopVideoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2634,7 +2808,20 @@ class SubscribeSetModeRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeSetModeRequest) + enum : int { + kStopVideoFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; + void clear_stop_video_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback stop_video_feedback() const; + void set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_feedback() const; + void _internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoRequest) private: class _Internal; @@ -2642,29 +2829,32 @@ class SubscribeSetModeRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + int stop_video_feedback_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SetModeResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetModeResponse) */ { +class RespondStopVideoResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoResponse) */ { public: - inline SetModeResponse() : SetModeResponse(nullptr) {} - ~SetModeResponse() override; + inline RespondStopVideoResponse() : RespondStopVideoResponse(nullptr) {} + ~RespondStopVideoResponse() override; template - explicit PROTOBUF_CONSTEXPR SetModeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SetModeResponse(const SetModeResponse& from); - SetModeResponse(SetModeResponse&& from) noexcept - : SetModeResponse() { + RespondStopVideoResponse(const RespondStopVideoResponse& from); + RespondStopVideoResponse(RespondStopVideoResponse&& from) noexcept + : RespondStopVideoResponse() { *this = ::std::move(from); } - inline SetModeResponse& operator=(const SetModeResponse& from) { + inline RespondStopVideoResponse& operator=(const RespondStopVideoResponse& from) { CopyFrom(from); return *this; } - inline SetModeResponse& operator=(SetModeResponse&& from) noexcept { + inline RespondStopVideoResponse& operator=(RespondStopVideoResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2694,20 +2884,20 @@ class SetModeResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetModeResponse& default_instance() { + static const RespondStopVideoResponse& default_instance() { return *internal_default_instance(); } - static inline const SetModeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetModeResponse_default_instance_); + static inline const RespondStopVideoResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = 15; - friend void swap(SetModeResponse& a, SetModeResponse& b) { + friend void swap(RespondStopVideoResponse& a, RespondStopVideoResponse& b) { a.Swap(&b); } - inline void Swap(SetModeResponse* other) { + inline void Swap(RespondStopVideoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2720,7 +2910,7 @@ class SetModeResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetModeResponse* other) { + void UnsafeArenaSwap(RespondStopVideoResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2728,14 +2918,14 @@ class SetModeResponse final : // implements Message ---------------------------------------------- - SetModeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStopVideoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const SetModeResponse& from); + void CopyFrom(const RespondStopVideoResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const SetModeResponse& from) { - SetModeResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStopVideoResponse& from) { + RespondStopVideoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -2753,15 +2943,15 @@ class SetModeResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(SetModeResponse* other); + void InternalSwap(RespondStopVideoResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SetModeResponse"; + return "mavsdk.rpc.camera_server.RespondStopVideoResponse"; } protected: - explicit SetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStopVideoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2774,19 +2964,23 @@ class SetModeResponse final : // accessors ------------------------------------------------------- enum : int { - kModeFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.Mode mode = 1; - void clear_mode() ; - ::mavsdk::rpc::camera_server::Mode mode() const; - void set_mode(::mavsdk::rpc::camera_server::Mode value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - ::mavsdk::rpc::camera_server::Mode _internal_mode() const; - void _internal_set_mode(::mavsdk::rpc::camera_server::Mode value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetModeResponse) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoResponse) private: class _Internal; @@ -2794,31 +2988,32 @@ class SetModeResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - int mode_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeStorageInformationRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) */ { +class SubscribeStartVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) */ { public: - inline SubscribeStorageInformationRequest() : SubscribeStorageInformationRequest(nullptr) {} + inline SubscribeStartVideoStreamingRequest() : SubscribeStartVideoStreamingRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from); - SubscribeStorageInformationRequest(SubscribeStorageInformationRequest&& from) noexcept - : SubscribeStorageInformationRequest() { + SubscribeStartVideoStreamingRequest(const SubscribeStartVideoStreamingRequest& from); + SubscribeStartVideoStreamingRequest(SubscribeStartVideoStreamingRequest&& from) noexcept + : SubscribeStartVideoStreamingRequest() { *this = ::std::move(from); } - inline SubscribeStorageInformationRequest& operator=(const SubscribeStorageInformationRequest& from) { + inline SubscribeStartVideoStreamingRequest& operator=(const SubscribeStartVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStorageInformationRequest& operator=(SubscribeStorageInformationRequest&& from) noexcept { + inline SubscribeStartVideoStreamingRequest& operator=(SubscribeStartVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2848,20 +3043,20 @@ class SubscribeStorageInformationRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStorageInformationRequest& default_instance() { + static const SubscribeStartVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStorageInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStorageInformationRequest_default_instance_); + static inline const SubscribeStartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = 16; - friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { + friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStorageInformationRequest* other) { + inline void Swap(SubscribeStartVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2874,7 +3069,7 @@ class SubscribeStorageInformationRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStorageInformationRequest* other) { + void UnsafeArenaSwap(SubscribeStartVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2882,15 +3077,15 @@ class SubscribeStorageInformationRequest final : // implements Message ---------------------------------------------- - SubscribeStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStartVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStorageInformationRequest& from) { + inline void CopyFrom(const SubscribeStartVideoStreamingRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStorageInformationRequest& from) { + void MergeFrom(const SubscribeStartVideoStreamingRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2898,10 +3093,10 @@ class SubscribeStorageInformationRequest final : private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeStorageInformationRequest"; + return "mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest"; } protected: - explicit SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2913,7 +3108,7 @@ class SubscribeStorageInformationRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStartVideoStreamingRequest) private: class _Internal; @@ -2925,25 +3120,25 @@ class SubscribeStorageInformationRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StorageInformationResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformationResponse) */ { +class StartVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StartVideoStreamingResponse) */ { public: - inline StorageInformationResponse() : StorageInformationResponse(nullptr) {} - ~StorageInformationResponse() override; + inline StartVideoStreamingResponse() : StartVideoStreamingResponse(nullptr) {} + ~StartVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StorageInformationResponse(const StorageInformationResponse& from); - StorageInformationResponse(StorageInformationResponse&& from) noexcept - : StorageInformationResponse() { + StartVideoStreamingResponse(const StartVideoStreamingResponse& from); + StartVideoStreamingResponse(StartVideoStreamingResponse&& from) noexcept + : StartVideoStreamingResponse() { *this = ::std::move(from); } - inline StorageInformationResponse& operator=(const StorageInformationResponse& from) { + inline StartVideoStreamingResponse& operator=(const StartVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline StorageInformationResponse& operator=(StorageInformationResponse&& from) noexcept { + inline StartVideoStreamingResponse& operator=(StartVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2973,20 +3168,20 @@ class StorageInformationResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StorageInformationResponse& default_instance() { + static const StartVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const StorageInformationResponse* internal_default_instance() { - return reinterpret_cast( - &_StorageInformationResponse_default_instance_); + static inline const StartVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StartVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = 17; - friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { + friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(StorageInformationResponse* other) { + inline void Swap(StartVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2999,7 +3194,7 @@ class StorageInformationResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StorageInformationResponse* other) { + void UnsafeArenaSwap(StartVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3007,14 +3202,14 @@ class StorageInformationResponse final : // implements Message ---------------------------------------------- - StorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StartVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StorageInformationResponse& from); + void CopyFrom(const StartVideoStreamingResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StorageInformationResponse& from) { - StorageInformationResponse::MergeImpl(*this, from); + void MergeFrom( const StartVideoStreamingResponse& from) { + StartVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3032,15 +3227,15 @@ class StorageInformationResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StorageInformationResponse* other); + void InternalSwap(StartVideoStreamingResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StorageInformationResponse"; + return "mavsdk.rpc.camera_server.StartVideoStreamingResponse"; } protected: - explicit StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3053,19 +3248,19 @@ class StorageInformationResponse final : // accessors ------------------------------------------------------- enum : int { - kStorageIdFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // int32 storage_id = 1; - void clear_storage_id() ; - ::int32_t storage_id() const; - void set_storage_id(::int32_t value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::int32_t _internal_storage_id() const; - void _internal_set_storage_id(::int32_t value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformationResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StartVideoStreamingResponse) private: class _Internal; @@ -3073,32 +3268,32 @@ class StorageInformationResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t storage_id_; + ::int32_t stream_id_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStorageInformationRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationRequest) */ { +class RespondStartVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) */ { public: - inline RespondStorageInformationRequest() : RespondStorageInformationRequest(nullptr) {} - ~RespondStorageInformationRequest() override; + inline RespondStartVideoStreamingRequest() : RespondStartVideoStreamingRequest(nullptr) {} + ~RespondStartVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondStorageInformationRequest(const RespondStorageInformationRequest& from); - RespondStorageInformationRequest(RespondStorageInformationRequest&& from) noexcept - : RespondStorageInformationRequest() { + RespondStartVideoStreamingRequest(const RespondStartVideoStreamingRequest& from); + RespondStartVideoStreamingRequest(RespondStartVideoStreamingRequest&& from) noexcept + : RespondStartVideoStreamingRequest() { *this = ::std::move(from); } - inline RespondStorageInformationRequest& operator=(const RespondStorageInformationRequest& from) { + inline RespondStartVideoStreamingRequest& operator=(const RespondStartVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline RespondStorageInformationRequest& operator=(RespondStorageInformationRequest&& from) noexcept { + inline RespondStartVideoStreamingRequest& operator=(RespondStartVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3128,20 +3323,20 @@ class RespondStorageInformationRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStorageInformationRequest& default_instance() { + static const RespondStartVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondStorageInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondStorageInformationRequest_default_instance_); + static inline const RespondStartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = 18; - friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { + friend void swap(RespondStartVideoStreamingRequest& a, RespondStartVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(RespondStorageInformationRequest* other) { + inline void Swap(RespondStartVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3154,7 +3349,7 @@ class RespondStorageInformationRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStorageInformationRequest* other) { + void UnsafeArenaSwap(RespondStartVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3162,14 +3357,14 @@ class RespondStorageInformationRequest final : // implements Message ---------------------------------------------- - RespondStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStartVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondStorageInformationRequest& from); + void CopyFrom(const RespondStartVideoStreamingRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondStorageInformationRequest& from) { - RespondStorageInformationRequest::MergeImpl(*this, from); + void MergeFrom( const RespondStartVideoStreamingRequest& from) { + RespondStartVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3187,15 +3382,15 @@ class RespondStorageInformationRequest final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondStorageInformationRequest* other); + void InternalSwap(RespondStartVideoStreamingRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStorageInformationRequest"; + return "mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest"; } protected: - explicit RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStartVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3208,23 +3403,19 @@ class RespondStorageInformationRequest final : // accessors ------------------------------------------------------- enum : int { - kStorageInformationFieldNumber = 1, + kStartVideoStreamingFeedbackFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; - bool has_storage_information() const; - void clear_storage_information() ; - const ::mavsdk::rpc::camera_server::StorageInformation& storage_information() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::StorageInformation* release_storage_information(); - ::mavsdk::rpc::camera_server::StorageInformation* mutable_storage_information(); - void set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* storage_information); + // .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; + void clear_start_video_streaming_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback start_video_streaming_feedback() const; + void set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + private: - const ::mavsdk::rpc::camera_server::StorageInformation& _internal_storage_information() const; - ::mavsdk::rpc::camera_server::StorageInformation* _internal_mutable_storage_information(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_start_video_streaming_feedback() const; + void _internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + public: - void unsafe_arena_set_allocated_storage_information( - ::mavsdk::rpc::camera_server::StorageInformation* storage_information); - ::mavsdk::rpc::camera_server::StorageInformation* unsafe_arena_release_storage_information(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest) private: class _Internal; @@ -3232,33 +3423,32 @@ class RespondStorageInformationRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + int start_video_streaming_feedback_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::StorageInformation* storage_information_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondStorageInformationResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationResponse) */ { +class RespondStartVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) */ { public: - inline RespondStorageInformationResponse() : RespondStorageInformationResponse(nullptr) {} - ~RespondStorageInformationResponse() override; + inline RespondStartVideoStreamingResponse() : RespondStartVideoStreamingResponse(nullptr) {} + ~RespondStartVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondStorageInformationResponse(const RespondStorageInformationResponse& from); - RespondStorageInformationResponse(RespondStorageInformationResponse&& from) noexcept - : RespondStorageInformationResponse() { + RespondStartVideoStreamingResponse(const RespondStartVideoStreamingResponse& from); + RespondStartVideoStreamingResponse(RespondStartVideoStreamingResponse&& from) noexcept + : RespondStartVideoStreamingResponse() { *this = ::std::move(from); } - inline RespondStorageInformationResponse& operator=(const RespondStorageInformationResponse& from) { + inline RespondStartVideoStreamingResponse& operator=(const RespondStartVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline RespondStorageInformationResponse& operator=(RespondStorageInformationResponse&& from) noexcept { + inline RespondStartVideoStreamingResponse& operator=(RespondStartVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3288,20 +3478,20 @@ class RespondStorageInformationResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondStorageInformationResponse& default_instance() { + static const RespondStartVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondStorageInformationResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondStorageInformationResponse_default_instance_); + static inline const RespondStartVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStartVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = 19; - friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { + friend void swap(RespondStartVideoStreamingResponse& a, RespondStartVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(RespondStorageInformationResponse* other) { + inline void Swap(RespondStartVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3314,7 +3504,7 @@ class RespondStorageInformationResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondStorageInformationResponse* other) { + void UnsafeArenaSwap(RespondStartVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3322,14 +3512,14 @@ class RespondStorageInformationResponse final : // implements Message ---------------------------------------------- - RespondStorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStartVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondStorageInformationResponse& from); + void CopyFrom(const RespondStartVideoStreamingResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondStorageInformationResponse& from) { - RespondStorageInformationResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStartVideoStreamingResponse& from) { + RespondStartVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3347,15 +3537,15 @@ class RespondStorageInformationResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondStorageInformationResponse* other); + void InternalSwap(RespondStartVideoStreamingResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondStorageInformationResponse"; + return "mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse"; } protected: - explicit RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStartVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3384,7 +3574,7 @@ class RespondStorageInformationResponse final : void unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse) private: class _Internal; @@ -3400,24 +3590,24 @@ class RespondStorageInformationResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeCaptureStatusRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) */ { +class SubscribeStopVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) */ { public: - inline SubscribeCaptureStatusRequest() : SubscribeCaptureStatusRequest(nullptr) {} + inline SubscribeStopVideoStreamingRequest() : SubscribeStopVideoStreamingRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from); - SubscribeCaptureStatusRequest(SubscribeCaptureStatusRequest&& from) noexcept - : SubscribeCaptureStatusRequest() { + SubscribeStopVideoStreamingRequest(const SubscribeStopVideoStreamingRequest& from); + SubscribeStopVideoStreamingRequest(SubscribeStopVideoStreamingRequest&& from) noexcept + : SubscribeStopVideoStreamingRequest() { *this = ::std::move(from); } - inline SubscribeCaptureStatusRequest& operator=(const SubscribeCaptureStatusRequest& from) { + inline SubscribeStopVideoStreamingRequest& operator=(const SubscribeStopVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCaptureStatusRequest& operator=(SubscribeCaptureStatusRequest&& from) noexcept { + inline SubscribeStopVideoStreamingRequest& operator=(SubscribeStopVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3447,20 +3637,20 @@ class SubscribeCaptureStatusRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCaptureStatusRequest& default_instance() { + static const SubscribeStopVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCaptureStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCaptureStatusRequest_default_instance_); + static inline const SubscribeStopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = 20; - friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { + friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCaptureStatusRequest* other) { + inline void Swap(SubscribeStopVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3473,7 +3663,7 @@ class SubscribeCaptureStatusRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCaptureStatusRequest* other) { + void UnsafeArenaSwap(SubscribeStopVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3481,15 +3671,15 @@ class SubscribeCaptureStatusRequest final : // implements Message ---------------------------------------------- - SubscribeCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStopVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCaptureStatusRequest& from) { + inline void CopyFrom(const SubscribeStopVideoStreamingRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCaptureStatusRequest& from) { + void MergeFrom(const SubscribeStopVideoStreamingRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -3497,10 +3687,10 @@ class SubscribeCaptureStatusRequest final : private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest"; + return "mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest"; } protected: - explicit SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3512,7 +3702,7 @@ class SubscribeCaptureStatusRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStopVideoStreamingRequest) private: class _Internal; @@ -3524,25 +3714,25 @@ class SubscribeCaptureStatusRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureStatusResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatusResponse) */ { +class StopVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StopVideoStreamingResponse) */ { public: - inline CaptureStatusResponse() : CaptureStatusResponse(nullptr) {} - ~CaptureStatusResponse() override; + inline StopVideoStreamingResponse() : StopVideoStreamingResponse(nullptr) {} + ~StopVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CaptureStatusResponse(const CaptureStatusResponse& from); - CaptureStatusResponse(CaptureStatusResponse&& from) noexcept - : CaptureStatusResponse() { + StopVideoStreamingResponse(const StopVideoStreamingResponse& from); + StopVideoStreamingResponse(StopVideoStreamingResponse&& from) noexcept + : StopVideoStreamingResponse() { *this = ::std::move(from); } - inline CaptureStatusResponse& operator=(const CaptureStatusResponse& from) { + inline StopVideoStreamingResponse& operator=(const StopVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline CaptureStatusResponse& operator=(CaptureStatusResponse&& from) noexcept { + inline StopVideoStreamingResponse& operator=(StopVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3572,20 +3762,20 @@ class CaptureStatusResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureStatusResponse& default_instance() { + static const StopVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const CaptureStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_CaptureStatusResponse_default_instance_); + static inline const StopVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_StopVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = 21; - friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { + friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(CaptureStatusResponse* other) { + inline void Swap(StopVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3598,7 +3788,7 @@ class CaptureStatusResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureStatusResponse* other) { + void UnsafeArenaSwap(StopVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3606,14 +3796,14 @@ class CaptureStatusResponse final : // implements Message ---------------------------------------------- - CaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CaptureStatusResponse& from); + void CopyFrom(const StopVideoStreamingResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CaptureStatusResponse& from) { - CaptureStatusResponse::MergeImpl(*this, from); + void MergeFrom( const StopVideoStreamingResponse& from) { + StopVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3631,15 +3821,15 @@ class CaptureStatusResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CaptureStatusResponse* other); + void InternalSwap(StopVideoStreamingResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureStatusResponse"; + return "mavsdk.rpc.camera_server.StopVideoStreamingResponse"; } protected: - explicit CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3652,19 +3842,19 @@ class CaptureStatusResponse final : // accessors ------------------------------------------------------- enum : int { - kReservedFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // int32 reserved = 1; - void clear_reserved() ; - ::int32_t reserved() const; - void set_reserved(::int32_t value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::int32_t _internal_reserved() const; - void _internal_set_reserved(::int32_t value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StopVideoStreamingResponse) private: class _Internal; @@ -3672,32 +3862,32 @@ class CaptureStatusResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t reserved_; + ::int32_t stream_id_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondCaptureStatusRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) */ { +class RespondStopVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) */ { public: - inline RespondCaptureStatusRequest() : RespondCaptureStatusRequest(nullptr) {} - ~RespondCaptureStatusRequest() override; + inline RespondStopVideoStreamingRequest() : RespondStopVideoStreamingRequest(nullptr) {} + ~RespondStopVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from); - RespondCaptureStatusRequest(RespondCaptureStatusRequest&& from) noexcept - : RespondCaptureStatusRequest() { + RespondStopVideoStreamingRequest(const RespondStopVideoStreamingRequest& from); + RespondStopVideoStreamingRequest(RespondStopVideoStreamingRequest&& from) noexcept + : RespondStopVideoStreamingRequest() { *this = ::std::move(from); } - inline RespondCaptureStatusRequest& operator=(const RespondCaptureStatusRequest& from) { + inline RespondStopVideoStreamingRequest& operator=(const RespondStopVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline RespondCaptureStatusRequest& operator=(RespondCaptureStatusRequest&& from) noexcept { + inline RespondStopVideoStreamingRequest& operator=(RespondStopVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3727,20 +3917,20 @@ class RespondCaptureStatusRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondCaptureStatusRequest& default_instance() { + static const RespondStopVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondCaptureStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondCaptureStatusRequest_default_instance_); + static inline const RespondStopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = 22; - friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { + friend void swap(RespondStopVideoStreamingRequest& a, RespondStopVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(RespondCaptureStatusRequest* other) { + inline void Swap(RespondStopVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3753,7 +3943,7 @@ class RespondCaptureStatusRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondCaptureStatusRequest* other) { + void UnsafeArenaSwap(RespondStopVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3761,14 +3951,14 @@ class RespondCaptureStatusRequest final : // implements Message ---------------------------------------------- - RespondCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStopVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondCaptureStatusRequest& from); + void CopyFrom(const RespondStopVideoStreamingRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondCaptureStatusRequest& from) { - RespondCaptureStatusRequest::MergeImpl(*this, from); + void MergeFrom( const RespondStopVideoStreamingRequest& from) { + RespondStopVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3786,15 +3976,15 @@ class RespondCaptureStatusRequest final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondCaptureStatusRequest* other); + void InternalSwap(RespondStopVideoStreamingRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondCaptureStatusRequest"; + return "mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest"; } protected: - explicit RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStopVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3807,23 +3997,19 @@ class RespondCaptureStatusRequest final : // accessors ------------------------------------------------------- enum : int { - kCaptureStatusFieldNumber = 1, + kStopVideoStreamingFeedbackFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; - bool has_capture_status() const; - void clear_capture_status() ; - const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureStatus* release_capture_status(); - ::mavsdk::rpc::camera_server::CaptureStatus* mutable_capture_status(); - void set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* capture_status); + // .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; + void clear_stop_video_streaming_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback stop_video_streaming_feedback() const; + void set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + private: - const ::mavsdk::rpc::camera_server::CaptureStatus& _internal_capture_status() const; - ::mavsdk::rpc::camera_server::CaptureStatus* _internal_mutable_capture_status(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_stop_video_streaming_feedback() const; + void _internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + public: - void unsafe_arena_set_allocated_capture_status( - ::mavsdk::rpc::camera_server::CaptureStatus* capture_status); - ::mavsdk::rpc::camera_server::CaptureStatus* unsafe_arena_release_capture_status(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest) private: class _Internal; @@ -3831,33 +4017,32 @@ class RespondCaptureStatusRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + int stop_video_streaming_feedback_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CaptureStatus* capture_status_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondCaptureStatusResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) */ { +class RespondStopVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) */ { public: - inline RespondCaptureStatusResponse() : RespondCaptureStatusResponse(nullptr) {} - ~RespondCaptureStatusResponse() override; + inline RespondStopVideoStreamingResponse() : RespondStopVideoStreamingResponse(nullptr) {} + ~RespondStopVideoStreamingResponse() override; template - explicit PROTOBUF_CONSTEXPR RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from); - RespondCaptureStatusResponse(RespondCaptureStatusResponse&& from) noexcept - : RespondCaptureStatusResponse() { + RespondStopVideoStreamingResponse(const RespondStopVideoStreamingResponse& from); + RespondStopVideoStreamingResponse(RespondStopVideoStreamingResponse&& from) noexcept + : RespondStopVideoStreamingResponse() { *this = ::std::move(from); } - inline RespondCaptureStatusResponse& operator=(const RespondCaptureStatusResponse& from) { + inline RespondStopVideoStreamingResponse& operator=(const RespondStopVideoStreamingResponse& from) { CopyFrom(from); return *this; } - inline RespondCaptureStatusResponse& operator=(RespondCaptureStatusResponse&& from) noexcept { + inline RespondStopVideoStreamingResponse& operator=(RespondStopVideoStreamingResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3887,20 +4072,20 @@ class RespondCaptureStatusResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondCaptureStatusResponse& default_instance() { + static const RespondStopVideoStreamingResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondCaptureStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondCaptureStatusResponse_default_instance_); + static inline const RespondStopVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStopVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = 23; - friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { + friend void swap(RespondStopVideoStreamingResponse& a, RespondStopVideoStreamingResponse& b) { a.Swap(&b); } - inline void Swap(RespondCaptureStatusResponse* other) { + inline void Swap(RespondStopVideoStreamingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -3913,7 +4098,7 @@ class RespondCaptureStatusResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondCaptureStatusResponse* other) { + void UnsafeArenaSwap(RespondStopVideoStreamingResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -3921,14 +4106,14 @@ class RespondCaptureStatusResponse final : // implements Message ---------------------------------------------- - RespondCaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStopVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondCaptureStatusResponse& from); + void CopyFrom(const RespondStopVideoStreamingResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondCaptureStatusResponse& from) { - RespondCaptureStatusResponse::MergeImpl(*this, from); + void MergeFrom( const RespondStopVideoStreamingResponse& from) { + RespondStopVideoStreamingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -3946,15 +4131,15 @@ class RespondCaptureStatusResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondCaptureStatusResponse* other); + void InternalSwap(RespondStopVideoStreamingResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondCaptureStatusResponse"; + return "mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse"; } protected: - explicit RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStopVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3983,7 +4168,7 @@ class RespondCaptureStatusResponse final : void unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse) private: class _Internal; @@ -3999,24 +4184,24 @@ class RespondCaptureStatusResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeFormatStorageRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) */ { +class SubscribeSetModeRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeSetModeRequest) */ { public: - inline SubscribeFormatStorageRequest() : SubscribeFormatStorageRequest(nullptr) {} + inline SubscribeSetModeRequest() : SubscribeSetModeRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from); - SubscribeFormatStorageRequest(SubscribeFormatStorageRequest&& from) noexcept - : SubscribeFormatStorageRequest() { + SubscribeSetModeRequest(const SubscribeSetModeRequest& from); + SubscribeSetModeRequest(SubscribeSetModeRequest&& from) noexcept + : SubscribeSetModeRequest() { *this = ::std::move(from); } - inline SubscribeFormatStorageRequest& operator=(const SubscribeFormatStorageRequest& from) { + inline SubscribeSetModeRequest& operator=(const SubscribeSetModeRequest& from) { CopyFrom(from); return *this; } - inline SubscribeFormatStorageRequest& operator=(SubscribeFormatStorageRequest&& from) noexcept { + inline SubscribeSetModeRequest& operator=(SubscribeSetModeRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4046,20 +4231,20 @@ class SubscribeFormatStorageRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeFormatStorageRequest& default_instance() { + static const SubscribeSetModeRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeFormatStorageRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeFormatStorageRequest_default_instance_); + static inline const SubscribeSetModeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = 24; - friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { + friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeFormatStorageRequest* other) { + inline void Swap(SubscribeSetModeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4072,7 +4257,7 @@ class SubscribeFormatStorageRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeFormatStorageRequest* other) { + void UnsafeArenaSwap(SubscribeSetModeRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4080,15 +4265,15 @@ class SubscribeFormatStorageRequest final : // implements Message ---------------------------------------------- - SubscribeFormatStorageRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeSetModeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeFormatStorageRequest& from) { + inline void CopyFrom(const SubscribeSetModeRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeFormatStorageRequest& from) { + void MergeFrom(const SubscribeSetModeRequest& from) { ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -4096,10 +4281,10 @@ class SubscribeFormatStorageRequest final : private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeFormatStorageRequest"; + return "mavsdk.rpc.camera_server.SubscribeSetModeRequest"; } protected: - explicit SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4111,7 +4296,7 @@ class SubscribeFormatStorageRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeSetModeRequest) private: class _Internal; @@ -4123,25 +4308,25 @@ class SubscribeFormatStorageRequest final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class FormatStorageResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.FormatStorageResponse) */ { +class SetModeResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetModeResponse) */ { public: - inline FormatStorageResponse() : FormatStorageResponse(nullptr) {} - ~FormatStorageResponse() override; + inline SetModeResponse() : SetModeResponse(nullptr) {} + ~SetModeResponse() override; template - explicit PROTOBUF_CONSTEXPR FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetModeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - FormatStorageResponse(const FormatStorageResponse& from); - FormatStorageResponse(FormatStorageResponse&& from) noexcept - : FormatStorageResponse() { + SetModeResponse(const SetModeResponse& from); + SetModeResponse(SetModeResponse&& from) noexcept + : SetModeResponse() { *this = ::std::move(from); } - inline FormatStorageResponse& operator=(const FormatStorageResponse& from) { + inline SetModeResponse& operator=(const SetModeResponse& from) { CopyFrom(from); return *this; } - inline FormatStorageResponse& operator=(FormatStorageResponse&& from) noexcept { + inline SetModeResponse& operator=(SetModeResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4171,20 +4356,20 @@ class FormatStorageResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FormatStorageResponse& default_instance() { + static const SetModeResponse& default_instance() { return *internal_default_instance(); } - static inline const FormatStorageResponse* internal_default_instance() { - return reinterpret_cast( - &_FormatStorageResponse_default_instance_); + static inline const SetModeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = 25; - friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { + friend void swap(SetModeResponse& a, SetModeResponse& b) { a.Swap(&b); } - inline void Swap(FormatStorageResponse* other) { + inline void Swap(SetModeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4197,7 +4382,7 @@ class FormatStorageResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FormatStorageResponse* other) { + void UnsafeArenaSwap(SetModeResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4205,14 +4390,14 @@ class FormatStorageResponse final : // implements Message ---------------------------------------------- - FormatStorageResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetModeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const FormatStorageResponse& from); + void CopyFrom(const SetModeResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const FormatStorageResponse& from) { - FormatStorageResponse::MergeImpl(*this, from); + void MergeFrom( const SetModeResponse& from) { + SetModeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4230,15 +4415,15 @@ class FormatStorageResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(FormatStorageResponse* other); + void InternalSwap(SetModeResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.FormatStorageResponse"; + return "mavsdk.rpc.camera_server.SetModeResponse"; } protected: - explicit FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4251,19 +4436,19 @@ class FormatStorageResponse final : // accessors ------------------------------------------------------- enum : int { - kStorageIdFieldNumber = 1, + kModeFieldNumber = 1, }; - // int32 storage_id = 1; - void clear_storage_id() ; - ::int32_t storage_id() const; - void set_storage_id(::int32_t value); + // .mavsdk.rpc.camera_server.Mode mode = 1; + void clear_mode() ; + ::mavsdk::rpc::camera_server::Mode mode() const; + void set_mode(::mavsdk::rpc::camera_server::Mode value); private: - ::int32_t _internal_storage_id() const; - void _internal_set_storage_id(::int32_t value); + ::mavsdk::rpc::camera_server::Mode _internal_mode() const; + void _internal_set_mode(::mavsdk::rpc::camera_server::Mode value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.FormatStorageResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetModeResponse) private: class _Internal; @@ -4271,31 +4456,32 @@ class FormatStorageResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t storage_id_; + int mode_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class SubscribeResetSettingsRequest final : - public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) */ { +class RespondSetModeRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeRequest) */ { public: - inline SubscribeResetSettingsRequest() : SubscribeResetSettingsRequest(nullptr) {} + inline RespondSetModeRequest() : RespondSetModeRequest(nullptr) {} + ~RespondSetModeRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondSetModeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from); - SubscribeResetSettingsRequest(SubscribeResetSettingsRequest&& from) noexcept - : SubscribeResetSettingsRequest() { + RespondSetModeRequest(const RespondSetModeRequest& from); + RespondSetModeRequest(RespondSetModeRequest&& from) noexcept + : RespondSetModeRequest() { *this = ::std::move(from); } - inline SubscribeResetSettingsRequest& operator=(const SubscribeResetSettingsRequest& from) { + inline RespondSetModeRequest& operator=(const RespondSetModeRequest& from) { CopyFrom(from); return *this; } - inline SubscribeResetSettingsRequest& operator=(SubscribeResetSettingsRequest&& from) noexcept { + inline RespondSetModeRequest& operator=(RespondSetModeRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4325,20 +4511,20 @@ class SubscribeResetSettingsRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeResetSettingsRequest& default_instance() { + static const RespondSetModeRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeResetSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeResetSettingsRequest_default_instance_); + static inline const RespondSetModeRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = 26; - friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { + friend void swap(RespondSetModeRequest& a, RespondSetModeRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeResetSettingsRequest* other) { + inline void Swap(RespondSetModeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4351,7 +4537,7 @@ class SubscribeResetSettingsRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeResetSettingsRequest* other) { + void UnsafeArenaSwap(RespondSetModeRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4359,26 +4545,40 @@ class SubscribeResetSettingsRequest final : // implements Message ---------------------------------------------- - SubscribeResetSettingsRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondSetModeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeResetSettingsRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeResetSettingsRequest& from) { - ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondSetModeRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondSetModeRequest& from) { + RespondSetModeRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondSetModeRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.SubscribeResetSettingsRequest"; + return "mavsdk.rpc.camera_server.RespondSetModeRequest"; } protected: - explicit SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondSetModeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4390,7 +4590,20 @@ class SubscribeResetSettingsRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + enum : int { + kSetModeFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; + void clear_set_mode_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback set_mode_feedback() const; + void set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_set_mode_feedback() const; + void _internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondSetModeRequest) private: class _Internal; @@ -4398,29 +4611,32 @@ class SubscribeResetSettingsRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { + int set_mode_feedback_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class ResetSettingsResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ResetSettingsResponse) */ { +class RespondSetModeResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondSetModeResponse) */ { public: - inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} - ~ResetSettingsResponse() override; + inline RespondSetModeResponse() : RespondSetModeResponse(nullptr) {} + ~RespondSetModeResponse() override; template - explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondSetModeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - ResetSettingsResponse(const ResetSettingsResponse& from); - ResetSettingsResponse(ResetSettingsResponse&& from) noexcept - : ResetSettingsResponse() { + RespondSetModeResponse(const RespondSetModeResponse& from); + RespondSetModeResponse(RespondSetModeResponse&& from) noexcept + : RespondSetModeResponse() { *this = ::std::move(from); } - inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { + inline RespondSetModeResponse& operator=(const RespondSetModeResponse& from) { CopyFrom(from); return *this; } - inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { + inline RespondSetModeResponse& operator=(RespondSetModeResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4450,20 +4666,20 @@ class ResetSettingsResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ResetSettingsResponse& default_instance() { + static const RespondSetModeResponse& default_instance() { return *internal_default_instance(); } - static inline const ResetSettingsResponse* internal_default_instance() { - return reinterpret_cast( - &_ResetSettingsResponse_default_instance_); + static inline const RespondSetModeResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondSetModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = 27; - friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { + friend void swap(RespondSetModeResponse& a, RespondSetModeResponse& b) { a.Swap(&b); } - inline void Swap(ResetSettingsResponse* other) { + inline void Swap(RespondSetModeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4476,7 +4692,7 @@ class ResetSettingsResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ResetSettingsResponse* other) { + void UnsafeArenaSwap(RespondSetModeResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4484,14 +4700,14 @@ class ResetSettingsResponse final : // implements Message ---------------------------------------------- - ResetSettingsResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondSetModeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const ResetSettingsResponse& from); + void CopyFrom(const RespondSetModeResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const ResetSettingsResponse& from) { - ResetSettingsResponse::MergeImpl(*this, from); + void MergeFrom( const RespondSetModeResponse& from) { + RespondSetModeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4509,15 +4725,15 @@ class ResetSettingsResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(ResetSettingsResponse* other); + void InternalSwap(RespondSetModeResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.ResetSettingsResponse"; + return "mavsdk.rpc.camera_server.RespondSetModeResponse"; } protected: - explicit ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondSetModeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4530,19 +4746,23 @@ class ResetSettingsResponse final : // accessors ------------------------------------------------------- enum : int { - kReservedFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // int32 reserved = 1; - void clear_reserved() ; - ::int32_t reserved() const; - void set_reserved(::int32_t value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - ::int32_t _internal_reserved() const; - void _internal_set_reserved(::int32_t value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ResetSettingsResponse) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondSetModeResponse) private: class _Internal; @@ -4550,32 +4770,32 @@ class ResetSettingsResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::int32_t reserved_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoRequest final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoRequest) */ { +class SubscribeStorageInformationRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) */ { public: - inline RespondTakePhotoRequest() : RespondTakePhotoRequest(nullptr) {} - ~RespondTakePhotoRequest() override; + inline SubscribeStorageInformationRequest() : SubscribeStorageInformationRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoRequest(const RespondTakePhotoRequest& from); - RespondTakePhotoRequest(RespondTakePhotoRequest&& from) noexcept - : RespondTakePhotoRequest() { + SubscribeStorageInformationRequest(const SubscribeStorageInformationRequest& from); + SubscribeStorageInformationRequest(SubscribeStorageInformationRequest&& from) noexcept + : SubscribeStorageInformationRequest() { *this = ::std::move(from); } - inline RespondTakePhotoRequest& operator=(const RespondTakePhotoRequest& from) { + inline SubscribeStorageInformationRequest& operator=(const SubscribeStorageInformationRequest& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoRequest& operator=(RespondTakePhotoRequest&& from) noexcept { + inline SubscribeStorageInformationRequest& operator=(SubscribeStorageInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4605,20 +4825,20 @@ class RespondTakePhotoRequest final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoRequest& default_instance() { + static const SubscribeStorageInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoRequest_default_instance_); + static inline const SubscribeStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = 28; - friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { + friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoRequest* other) { + inline void Swap(SubscribeStorageInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4631,7 +4851,7 @@ class RespondTakePhotoRequest final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoRequest* other) { + void UnsafeArenaSwap(SubscribeStorageInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4639,40 +4859,26 @@ class RespondTakePhotoRequest final : // implements Message ---------------------------------------------- - RespondTakePhotoRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoRequest& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoRequest& from) { - RespondTakePhotoRequest::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeStorageInformationRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeStorageInformationRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoRequest"; + return "mavsdk.rpc.camera_server.SubscribeStorageInformationRequest"; } protected: - explicit RespondTakePhotoRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4684,35 +4890,7 @@ class RespondTakePhotoRequest final : // accessors ------------------------------------------------------- - enum : int { - kCaptureInfoFieldNumber = 2, - kTakePhotoFeedbackFieldNumber = 1, - }; - // .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; - bool has_capture_info() const; - void clear_capture_info() ; - const ::mavsdk::rpc::camera_server::CaptureInfo& capture_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureInfo* release_capture_info(); - ::mavsdk::rpc::camera_server::CaptureInfo* mutable_capture_info(); - void set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - private: - const ::mavsdk::rpc::camera_server::CaptureInfo& _internal_capture_info() const; - ::mavsdk::rpc::camera_server::CaptureInfo* _internal_mutable_capture_info(); - public: - void unsafe_arena_set_allocated_capture_info( - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info); - ::mavsdk::rpc::camera_server::CaptureInfo* unsafe_arena_release_capture_info(); - // .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; - void clear_take_photo_feedback() ; - ::mavsdk::rpc::camera_server::TakePhotoFeedback take_photo_feedback() const; - void set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - private: - ::mavsdk::rpc::camera_server::TakePhotoFeedback _internal_take_photo_feedback() const; - void _internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeStorageInformationRequest) private: class _Internal; @@ -4720,34 +4898,29 @@ class RespondTakePhotoRequest final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info_; - int take_photo_feedback_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class RespondTakePhotoResponse final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondTakePhotoResponse) */ { +class StorageInformationResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformationResponse) */ { public: - inline RespondTakePhotoResponse() : RespondTakePhotoResponse(nullptr) {} - ~RespondTakePhotoResponse() override; - template - explicit PROTOBUF_CONSTEXPR RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + inline StorageInformationResponse() : StorageInformationResponse(nullptr) {} + ~StorageInformationResponse() override; + template + explicit PROTOBUF_CONSTEXPR StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - RespondTakePhotoResponse(const RespondTakePhotoResponse& from); - RespondTakePhotoResponse(RespondTakePhotoResponse&& from) noexcept - : RespondTakePhotoResponse() { + StorageInformationResponse(const StorageInformationResponse& from); + StorageInformationResponse(StorageInformationResponse&& from) noexcept + : StorageInformationResponse() { *this = ::std::move(from); } - inline RespondTakePhotoResponse& operator=(const RespondTakePhotoResponse& from) { + inline StorageInformationResponse& operator=(const StorageInformationResponse& from) { CopyFrom(from); return *this; } - inline RespondTakePhotoResponse& operator=(RespondTakePhotoResponse&& from) noexcept { + inline StorageInformationResponse& operator=(StorageInformationResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4777,20 +4950,20 @@ class RespondTakePhotoResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RespondTakePhotoResponse& default_instance() { + static const StorageInformationResponse& default_instance() { return *internal_default_instance(); } - static inline const RespondTakePhotoResponse* internal_default_instance() { - return reinterpret_cast( - &_RespondTakePhotoResponse_default_instance_); + static inline const StorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_StorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = 29; - friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { + friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { a.Swap(&b); } - inline void Swap(RespondTakePhotoResponse* other) { + inline void Swap(StorageInformationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4803,7 +4976,7 @@ class RespondTakePhotoResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RespondTakePhotoResponse* other) { + void UnsafeArenaSwap(StorageInformationResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4811,14 +4984,14 @@ class RespondTakePhotoResponse final : // implements Message ---------------------------------------------- - RespondTakePhotoResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const RespondTakePhotoResponse& from); + void CopyFrom(const StorageInformationResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const RespondTakePhotoResponse& from) { - RespondTakePhotoResponse::MergeImpl(*this, from); + void MergeFrom( const StorageInformationResponse& from) { + StorageInformationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4836,15 +5009,15 @@ class RespondTakePhotoResponse final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RespondTakePhotoResponse* other); + void InternalSwap(StorageInformationResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.RespondTakePhotoResponse"; + return "mavsdk.rpc.camera_server.StorageInformationResponse"; } protected: - explicit RespondTakePhotoResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit StorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -4857,23 +5030,19 @@ class RespondTakePhotoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraServerResultFieldNumber = 1, + kStorageIdFieldNumber = 1, }; - // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; - bool has_camera_server_result() const; - void clear_camera_server_result() ; - const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); - ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); - void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); + private: - const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; - ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); + public: - void unsafe_arena_set_allocated_camera_server_result( - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); - ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondTakePhotoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformationResponse) private: class _Internal; @@ -4881,33 +5050,32 @@ class RespondTakePhotoResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + ::int32_t storage_id_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Information final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { +class RespondStorageInformationRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationRequest) */ { public: - inline Information() : Information(nullptr) {} - ~Information() override; + inline RespondStorageInformationRequest() : RespondStorageInformationRequest(nullptr) {} + ~RespondStorageInformationRequest() override; template - explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Information(const Information& from); - Information(Information&& from) noexcept - : Information() { + RespondStorageInformationRequest(const RespondStorageInformationRequest& from); + RespondStorageInformationRequest(RespondStorageInformationRequest&& from) noexcept + : RespondStorageInformationRequest() { *this = ::std::move(from); } - inline Information& operator=(const Information& from) { + inline RespondStorageInformationRequest& operator=(const RespondStorageInformationRequest& from) { CopyFrom(from); return *this; } - inline Information& operator=(Information&& from) noexcept { + inline RespondStorageInformationRequest& operator=(RespondStorageInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4937,20 +5105,20 @@ class Information final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Information& default_instance() { + static const RespondStorageInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const Information* internal_default_instance() { - return reinterpret_cast( - &_Information_default_instance_); + static inline const RespondStorageInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = 30; - friend void swap(Information& a, Information& b) { + friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { a.Swap(&b); } - inline void Swap(Information* other) { + inline void Swap(RespondStorageInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -4963,7 +5131,7 @@ class Information final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Information* other) { + void UnsafeArenaSwap(RespondStorageInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -4971,14 +5139,14 @@ class Information final : // implements Message ---------------------------------------------- - Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStorageInformationRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Information& from); + void CopyFrom(const RespondStorageInformationRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Information& from) { - Information::MergeImpl(*this, from); + void MergeFrom( const RespondStorageInformationRequest& from) { + RespondStorageInformationRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -4996,15 +5164,15 @@ class Information final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Information* other); + void InternalSwap(RespondStorageInformationRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Information"; + return "mavsdk.rpc.camera_server.RespondStorageInformationRequest"; } protected: - explicit Information(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStorageInformationRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -5017,231 +5185,88 @@ class Information final : // accessors ------------------------------------------------------- enum : int { - kVendorNameFieldNumber = 1, - kModelNameFieldNumber = 2, - kFirmwareVersionFieldNumber = 3, - kDefinitionFileUriFieldNumber = 11, - kFocalLengthMmFieldNumber = 4, - kHorizontalSensorSizeMmFieldNumber = 5, - kVerticalSensorSizeMmFieldNumber = 6, - kHorizontalResolutionPxFieldNumber = 7, - kVerticalResolutionPxFieldNumber = 8, - kLensIdFieldNumber = 9, - kDefinitionFileVersionFieldNumber = 10, + kStorageInformationFieldNumber = 2, + kStorageInformationFeedbackFieldNumber = 1, }; - // string vendor_name = 1; - void clear_vendor_name() ; - const std::string& vendor_name() const; - - - - - template - void set_vendor_name(Arg_&& arg, Args_... args); - std::string* mutable_vendor_name(); - PROTOBUF_NODISCARD std::string* release_vendor_name(); - void set_allocated_vendor_name(std::string* ptr); - + // .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; + bool has_storage_information() const; + void clear_storage_information() ; + const ::mavsdk::rpc::camera_server::StorageInformation& storage_information() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::StorageInformation* release_storage_information(); + ::mavsdk::rpc::camera_server::StorageInformation* mutable_storage_information(); + void set_allocated_storage_information(::mavsdk::rpc::camera_server::StorageInformation* storage_information); private: - const std::string& _internal_vendor_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( - const std::string& value); - std::string* _internal_mutable_vendor_name(); - + const ::mavsdk::rpc::camera_server::StorageInformation& _internal_storage_information() const; + ::mavsdk::rpc::camera_server::StorageInformation* _internal_mutable_storage_information(); public: - // string model_name = 2; - void clear_model_name() ; - const std::string& model_name() const; - - - - - template - void set_model_name(Arg_&& arg, Args_... args); - std::string* mutable_model_name(); - PROTOBUF_NODISCARD std::string* release_model_name(); - void set_allocated_model_name(std::string* ptr); + void unsafe_arena_set_allocated_storage_information( + ::mavsdk::rpc::camera_server::StorageInformation* storage_information); + ::mavsdk::rpc::camera_server::StorageInformation* unsafe_arena_release_storage_information(); + // .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; + void clear_storage_information_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback storage_information_feedback() const; + void set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - const std::string& _internal_model_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( - const std::string& value); - std::string* _internal_mutable_model_name(); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_storage_information_feedback() const; + void _internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // string firmware_version = 3; - void clear_firmware_version() ; - const std::string& firmware_version() const; - - - - - template - void set_firmware_version(Arg_&& arg, Args_... args); - std::string* mutable_firmware_version(); - PROTOBUF_NODISCARD std::string* release_firmware_version(); - void set_allocated_firmware_version(std::string* ptr); - - private: - const std::string& _internal_firmware_version() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version( - const std::string& value); - std::string* _internal_mutable_firmware_version(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationRequest) + private: + class _Internal; - public: - // string definition_file_uri = 11; - void clear_definition_file_uri() ; - const std::string& definition_file_uri() const; + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::StorageInformation* storage_information_; + int storage_information_feedback_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- +class RespondStorageInformationResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondStorageInformationResponse) */ { + public: + inline RespondStorageInformationResponse() : RespondStorageInformationResponse(nullptr) {} + ~RespondStorageInformationResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + RespondStorageInformationResponse(const RespondStorageInformationResponse& from); + RespondStorageInformationResponse(RespondStorageInformationResponse&& from) noexcept + : RespondStorageInformationResponse() { + *this = ::std::move(from); + } + inline RespondStorageInformationResponse& operator=(const RespondStorageInformationResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondStorageInformationResponse& operator=(RespondStorageInformationResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } - template - void set_definition_file_uri(Arg_&& arg, Args_... args); - std::string* mutable_definition_file_uri(); - PROTOBUF_NODISCARD std::string* release_definition_file_uri(); - void set_allocated_definition_file_uri(std::string* ptr); - - private: - const std::string& _internal_definition_file_uri() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri( - const std::string& value); - std::string* _internal_mutable_definition_file_uri(); - - public: - // float focal_length_mm = 4; - void clear_focal_length_mm() ; - float focal_length_mm() const; - void set_focal_length_mm(float value); - - private: - float _internal_focal_length_mm() const; - void _internal_set_focal_length_mm(float value); - - public: - // float horizontal_sensor_size_mm = 5; - void clear_horizontal_sensor_size_mm() ; - float horizontal_sensor_size_mm() const; - void set_horizontal_sensor_size_mm(float value); - - private: - float _internal_horizontal_sensor_size_mm() const; - void _internal_set_horizontal_sensor_size_mm(float value); - - public: - // float vertical_sensor_size_mm = 6; - void clear_vertical_sensor_size_mm() ; - float vertical_sensor_size_mm() const; - void set_vertical_sensor_size_mm(float value); - - private: - float _internal_vertical_sensor_size_mm() const; - void _internal_set_vertical_sensor_size_mm(float value); - - public: - // uint32 horizontal_resolution_px = 7; - void clear_horizontal_resolution_px() ; - ::uint32_t horizontal_resolution_px() const; - void set_horizontal_resolution_px(::uint32_t value); - - private: - ::uint32_t _internal_horizontal_resolution_px() const; - void _internal_set_horizontal_resolution_px(::uint32_t value); - - public: - // uint32 vertical_resolution_px = 8; - void clear_vertical_resolution_px() ; - ::uint32_t vertical_resolution_px() const; - void set_vertical_resolution_px(::uint32_t value); - - private: - ::uint32_t _internal_vertical_resolution_px() const; - void _internal_set_vertical_resolution_px(::uint32_t value); - - public: - // uint32 lens_id = 9; - void clear_lens_id() ; - ::uint32_t lens_id() const; - void set_lens_id(::uint32_t value); - - private: - ::uint32_t _internal_lens_id() const; - void _internal_set_lens_id(::uint32_t value); - - public: - // uint32 definition_file_version = 10; - void clear_definition_file_version() ; - ::uint32_t definition_file_version() const; - void set_definition_file_version(::uint32_t value); - - private: - ::uint32_t _internal_definition_file_version() const; - void _internal_set_definition_file_version(::uint32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) - private: - class _Internal; - - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; - float focal_length_mm_; - float horizontal_sensor_size_mm_; - float vertical_sensor_size_mm_; - ::uint32_t horizontal_resolution_px_; - ::uint32_t vertical_resolution_px_; - ::uint32_t lens_id_; - ::uint32_t definition_file_version_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -};// ------------------------------------------------------------------- - -class Position final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { - public: - inline Position() : Position(nullptr) {} - ~Position() override; - template - explicit PROTOBUF_CONSTEXPR Position(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - - Position(const Position& from); - Position(Position&& from) noexcept - : Position() { - *this = ::std::move(from); - } - - inline Position& operator=(const Position& from) { - CopyFrom(from); - return *this; - } - inline Position& operator=(Position&& from) noexcept { - if (this == &from) return *this; - if (GetOwningArena() == from.GetOwningArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetOwningArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { - return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); - } - inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { - return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); - } + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { return GetDescriptor(); @@ -5252,20 +5277,20 @@ class Position final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Position& default_instance() { + static const RespondStorageInformationResponse& default_instance() { return *internal_default_instance(); } - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const RespondStorageInformationResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondStorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = 31; - friend void swap(Position& a, Position& b) { + friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { a.Swap(&b); } - inline void Swap(Position* other) { + inline void Swap(RespondStorageInformationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -5278,7 +5303,7 @@ class Position final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Position* other) { + void UnsafeArenaSwap(RespondStorageInformationResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -5286,14 +5311,14 @@ class Position final : // implements Message ---------------------------------------------- - Position* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondStorageInformationResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Position& from); + void CopyFrom(const RespondStorageInformationResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Position& from) { - Position::MergeImpl(*this, from); + void MergeFrom( const RespondStorageInformationResponse& from) { + RespondStorageInformationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -5311,15 +5336,15 @@ class Position final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Position* other); + void InternalSwap(RespondStorageInformationResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Position"; + return "mavsdk.rpc.camera_server.RespondStorageInformationResponse"; } protected: - explicit Position(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondStorageInformationResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -5332,52 +5357,23 @@ class Position final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, - kRelativeAltitudeMFieldNumber = 4, + kCameraServerResultFieldNumber = 1, }; - // double latitude_deg = 1; - void clear_latitude_deg() ; - double latitude_deg() const; - void set_latitude_deg(double value); - - private: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); - - public: - // double longitude_deg = 2; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); - - private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); - - public: - // float absolute_altitude_m = 3; - void clear_absolute_altitude_m() ; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); - - private: - float _internal_absolute_altitude_m() const; - void _internal_set_absolute_altitude_m(float value); - - public: - // float relative_altitude_m = 4; - void clear_relative_altitude_m() ; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - float _internal_relative_altitude_m() const; - void _internal_set_relative_altitude_m(float value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondStorageInformationResponse) private: class _Internal; @@ -5385,35 +5381,32 @@ class Position final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - double latitude_deg_; - double longitude_deg_; - float absolute_altitude_m_; - float relative_altitude_m_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class Quaternion final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { +class SubscribeCaptureStatusRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline SubscribeCaptureStatusRequest() : SubscribeCaptureStatusRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR Quaternion(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - Quaternion(const Quaternion& from); - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + SubscribeCaptureStatusRequest(const SubscribeCaptureStatusRequest& from); + SubscribeCaptureStatusRequest(SubscribeCaptureStatusRequest&& from) noexcept + : SubscribeCaptureStatusRequest() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline SubscribeCaptureStatusRequest& operator=(const SubscribeCaptureStatusRequest& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline SubscribeCaptureStatusRequest& operator=(SubscribeCaptureStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5443,20 +5436,20 @@ class Quaternion final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const SubscribeCaptureStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const SubscribeCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCaptureStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = 32; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(SubscribeCaptureStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -5469,7 +5462,7 @@ class Quaternion final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(SubscribeCaptureStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -5477,14 +5470,139 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeCaptureStatusRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeCaptureStatusRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest"; + } + protected: + explicit SubscribeCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeCaptureStatusRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CaptureStatusResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatusResponse) */ { + public: + inline CaptureStatusResponse() : CaptureStatusResponse(nullptr) {} + ~CaptureStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CaptureStatusResponse(const CaptureStatusResponse& from); + CaptureStatusResponse(CaptureStatusResponse&& from) noexcept + : CaptureStatusResponse() { + *this = ::std::move(from); + } + + inline CaptureStatusResponse& operator=(const CaptureStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline CaptureStatusResponse& operator=(CaptureStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CaptureStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const CaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 33; + + friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(CaptureStatusResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CaptureStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const CaptureStatusResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const CaptureStatusResponse& from) { + CaptureStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -5502,15 +5620,15 @@ class Quaternion final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Quaternion* other); + void InternalSwap(CaptureStatusResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.Quaternion"; + return "mavsdk.rpc.camera_server.CaptureStatusResponse"; } protected: - explicit Quaternion(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit CaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -5523,52 +5641,19 @@ class Quaternion final : // accessors ------------------------------------------------------- enum : int { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, + kReservedFieldNumber = 1, }; - // float w = 1; - void clear_w() ; - float w() const; - void set_w(float value); - - private: - float _internal_w() const; - void _internal_set_w(float value); - - public: - // float x = 2; - void clear_x() ; - float x() const; - void set_x(float value); - - private: - float _internal_x() const; - void _internal_set_x(float value); - - public: - // float y = 3; - void clear_y() ; - float y() const; - void set_y(float value); - - private: - float _internal_y() const; - void _internal_set_y(float value); - - public: - // float z = 4; - void clear_z() ; - float z() const; - void set_z(float value); + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); private: - float _internal_z() const; - void _internal_set_z(float value); + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatusResponse) private: class _Internal; @@ -5576,35 +5661,32 @@ class Quaternion final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - float w_; - float x_; - float y_; - float z_; + ::int32_t reserved_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureInfo final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { +class RespondCaptureStatusRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) */ { public: - inline CaptureInfo() : CaptureInfo(nullptr) {} - ~CaptureInfo() override; + inline RespondCaptureStatusRequest() : RespondCaptureStatusRequest(nullptr) {} + ~RespondCaptureStatusRequest() override; template - explicit PROTOBUF_CONSTEXPR CaptureInfo(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CaptureInfo(const CaptureInfo& from); - CaptureInfo(CaptureInfo&& from) noexcept - : CaptureInfo() { + RespondCaptureStatusRequest(const RespondCaptureStatusRequest& from); + RespondCaptureStatusRequest(RespondCaptureStatusRequest&& from) noexcept + : RespondCaptureStatusRequest() { *this = ::std::move(from); } - inline CaptureInfo& operator=(const CaptureInfo& from) { + inline RespondCaptureStatusRequest& operator=(const RespondCaptureStatusRequest& from) { CopyFrom(from); return *this; } - inline CaptureInfo& operator=(CaptureInfo&& from) noexcept { + inline RespondCaptureStatusRequest& operator=(RespondCaptureStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5634,20 +5716,20 @@ class CaptureInfo final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureInfo& default_instance() { + static const RespondCaptureStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const CaptureInfo* internal_default_instance() { - return reinterpret_cast( - &_CaptureInfo_default_instance_); + static inline const RespondCaptureStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 33; + 34; - friend void swap(CaptureInfo& a, CaptureInfo& b) { + friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { a.Swap(&b); } - inline void Swap(CaptureInfo* other) { + inline void Swap(RespondCaptureStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -5660,7 +5742,7 @@ class CaptureInfo final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureInfo* other) { + void UnsafeArenaSwap(RespondCaptureStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -5668,14 +5750,14 @@ class CaptureInfo final : // implements Message ---------------------------------------------- - CaptureInfo* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondCaptureStatusRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CaptureInfo& from); + void CopyFrom(const RespondCaptureStatusRequest& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CaptureInfo& from) { - CaptureInfo::MergeImpl(*this, from); + void MergeFrom( const RespondCaptureStatusRequest& from) { + RespondCaptureStatusRequest::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -5693,15 +5775,15 @@ class CaptureInfo final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CaptureInfo* other); + void InternalSwap(RespondCaptureStatusRequest* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureInfo"; + return "mavsdk.rpc.camera_server.RespondCaptureStatusRequest"; } protected: - explicit CaptureInfo(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondCaptureStatusRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -5714,92 +5796,34 @@ class CaptureInfo final : // accessors ------------------------------------------------------- enum : int { - kFileUrlFieldNumber = 6, - kPositionFieldNumber = 1, - kAttitudeQuaternionFieldNumber = 2, - kTimeUtcUsFieldNumber = 3, - kIsSuccessFieldNumber = 4, - kIndexFieldNumber = 5, + kCaptureStatusFieldNumber = 2, + kCaptureStatusFeedbackFieldNumber = 1, }; - // string file_url = 6; - void clear_file_url() ; - const std::string& file_url() const; - - - - - template - void set_file_url(Arg_&& arg, Args_... args); - std::string* mutable_file_url(); - PROTOBUF_NODISCARD std::string* release_file_url(); - void set_allocated_file_url(std::string* ptr); - - private: - const std::string& _internal_file_url() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( - const std::string& value); - std::string* _internal_mutable_file_url(); - - public: - // .mavsdk.rpc.camera_server.Position position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::camera_server::Position& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); - ::mavsdk::rpc::camera_server::Position* mutable_position(); - void set_allocated_position(::mavsdk::rpc::camera_server::Position* position); - private: - const ::mavsdk::rpc::camera_server::Position& _internal_position() const; - ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); - public: - void unsafe_arena_set_allocated_position( - ::mavsdk::rpc::camera_server::Position* position); - ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); - // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; - bool has_attitude_quaternion() const; - void clear_attitude_quaternion() ; - const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); - ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); - void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); - private: - const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; - ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); - public: - void unsafe_arena_set_allocated_attitude_quaternion( - ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); - ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); - // uint64 time_utc_us = 3; - void clear_time_utc_us() ; - ::uint64_t time_utc_us() const; - void set_time_utc_us(::uint64_t value); - - private: - ::uint64_t _internal_time_utc_us() const; - void _internal_set_time_utc_us(::uint64_t value); - - public: - // bool is_success = 4; - void clear_is_success() ; - bool is_success() const; - void set_is_success(bool value); - + // .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; + bool has_capture_status() const; + void clear_capture_status() ; + const ::mavsdk::rpc::camera_server::CaptureStatus& capture_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CaptureStatus* release_capture_status(); + ::mavsdk::rpc::camera_server::CaptureStatus* mutable_capture_status(); + void set_allocated_capture_status(::mavsdk::rpc::camera_server::CaptureStatus* capture_status); private: - bool _internal_is_success() const; - void _internal_set_is_success(bool value); - + const ::mavsdk::rpc::camera_server::CaptureStatus& _internal_capture_status() const; + ::mavsdk::rpc::camera_server::CaptureStatus* _internal_mutable_capture_status(); public: - // int32 index = 5; - void clear_index() ; - ::int32_t index() const; - void set_index(::int32_t value); + void unsafe_arena_set_allocated_capture_status( + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status); + ::mavsdk::rpc::camera_server::CaptureStatus* unsafe_arena_release_capture_status(); + // .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; + void clear_capture_status_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback capture_status_feedback() const; + void set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - ::int32_t _internal_index() const; - void _internal_set_index(::int32_t value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_capture_status_feedback() const; + void _internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusRequest) private: class _Internal; @@ -5809,36 +5833,32 @@ class CaptureInfo final : struct Impl_ { ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr file_url_; - ::mavsdk::rpc::camera_server::Position* position_; - ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; - ::uint64_t time_utc_us_; - bool is_success_; - ::int32_t index_; + ::mavsdk::rpc::camera_server::CaptureStatus* capture_status_; + int capture_status_feedback_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CameraServerResult final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { +class RespondCaptureStatusResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) */ { public: - inline CameraServerResult() : CameraServerResult(nullptr) {} - ~CameraServerResult() override; + inline RespondCaptureStatusResponse() : RespondCaptureStatusResponse(nullptr) {} + ~RespondCaptureStatusResponse() override; template - explicit PROTOBUF_CONSTEXPR CameraServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CameraServerResult(const CameraServerResult& from); - CameraServerResult(CameraServerResult&& from) noexcept - : CameraServerResult() { + RespondCaptureStatusResponse(const RespondCaptureStatusResponse& from); + RespondCaptureStatusResponse(RespondCaptureStatusResponse&& from) noexcept + : RespondCaptureStatusResponse() { *this = ::std::move(from); } - inline CameraServerResult& operator=(const CameraServerResult& from) { + inline RespondCaptureStatusResponse& operator=(const RespondCaptureStatusResponse& from) { CopyFrom(from); return *this; } - inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { + inline RespondCaptureStatusResponse& operator=(RespondCaptureStatusResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5868,20 +5888,20 @@ class CameraServerResult final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CameraServerResult& default_instance() { + static const RespondCaptureStatusResponse& default_instance() { return *internal_default_instance(); } - static inline const CameraServerResult* internal_default_instance() { - return reinterpret_cast( - &_CameraServerResult_default_instance_); + static inline const RespondCaptureStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondCaptureStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 34; + 35; - friend void swap(CameraServerResult& a, CameraServerResult& b) { + friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { a.Swap(&b); } - inline void Swap(CameraServerResult* other) { + inline void Swap(RespondCaptureStatusResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -5894,7 +5914,7 @@ class CameraServerResult final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CameraServerResult* other) { + void UnsafeArenaSwap(RespondCaptureStatusResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -5902,14 +5922,14 @@ class CameraServerResult final : // implements Message ---------------------------------------------- - CameraServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RespondCaptureStatusResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CameraServerResult& from); + void CopyFrom(const RespondCaptureStatusResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CameraServerResult& from) { - CameraServerResult::MergeImpl(*this, from); + void MergeFrom( const RespondCaptureStatusResponse& from) { + RespondCaptureStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -5927,15 +5947,15 @@ class CameraServerResult final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CameraServerResult* other); + void InternalSwap(RespondCaptureStatusResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CameraServerResult"; + return "mavsdk.rpc.camera_server.RespondCaptureStatusResponse"; } protected: - explicit CameraServerResult(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit RespondCaptureStatusResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -5945,70 +5965,26 @@ class CameraServerResult final : // nested types ---------------------------------------------------- - using Result = CameraServerResult_Result; - static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; - static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; - static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; - static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; - static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; - static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; - static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; - static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; - static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; - static inline bool Result_IsValid(int value) { - return CameraServerResult_Result_IsValid(value); - } - static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; - static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; - static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Result_descriptor() { - return CameraServerResult_Result_descriptor(); - } - template - static inline const std::string& Result_Name(T value) { - return CameraServerResult_Result_Name(value); - } - static inline bool Result_Parse(absl::string_view name, Result* value) { - return CameraServerResult_Result_Parse(name, value); - } - // accessors ------------------------------------------------------- enum : int { - kResultStrFieldNumber = 2, - kResultFieldNumber = 1, + kCameraServerResultFieldNumber = 1, }; - // string result_str = 2; - void clear_result_str() ; - const std::string& result_str() const; - - - - - template - void set_result_str(Arg_&& arg, Args_... args); - std::string* mutable_result_str(); - PROTOBUF_NODISCARD std::string* release_result_str(); - void set_allocated_result_str(std::string* ptr); - - 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.camera_server.CameraServerResult.Result result = 1; - void clear_result() ; - ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; - void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); - + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); private: - ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; - void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); - + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondCaptureStatusResponse) private: class _Internal; @@ -6016,33 +5992,32 @@ class CameraServerResult final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; - int result_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class StorageInformation final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformation) */ { +class SubscribeFormatStorageRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) */ { public: - inline StorageInformation() : StorageInformation(nullptr) {} - ~StorageInformation() override; + inline SubscribeFormatStorageRequest() : SubscribeFormatStorageRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StorageInformation(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - StorageInformation(const StorageInformation& from); - StorageInformation(StorageInformation&& from) noexcept - : StorageInformation() { + SubscribeFormatStorageRequest(const SubscribeFormatStorageRequest& from); + SubscribeFormatStorageRequest(SubscribeFormatStorageRequest&& from) noexcept + : SubscribeFormatStorageRequest() { *this = ::std::move(from); } - inline StorageInformation& operator=(const StorageInformation& from) { + inline SubscribeFormatStorageRequest& operator=(const SubscribeFormatStorageRequest& from) { CopyFrom(from); return *this; } - inline StorageInformation& operator=(StorageInformation&& from) noexcept { + inline SubscribeFormatStorageRequest& operator=(SubscribeFormatStorageRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6072,20 +6047,20 @@ class StorageInformation final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StorageInformation& default_instance() { + static const SubscribeFormatStorageRequest& default_instance() { return *internal_default_instance(); } - static inline const StorageInformation* internal_default_instance() { - return reinterpret_cast( - &_StorageInformation_default_instance_); + static inline const SubscribeFormatStorageRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 35; + 36; - friend void swap(StorageInformation& a, StorageInformation& b) { + friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { a.Swap(&b); } - inline void Swap(StorageInformation* other) { + inline void Swap(SubscribeFormatStorageRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -6098,7 +6073,7 @@ class StorageInformation final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StorageInformation* other) { + void UnsafeArenaSwap(SubscribeFormatStorageRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -6106,40 +6081,26 @@ class StorageInformation final : // implements Message ---------------------------------------------- - StorageInformation* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeFormatStorageRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const StorageInformation& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const StorageInformation& from) { - StorageInformation::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeFormatStorageRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeFormatStorageRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(StorageInformation* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.StorageInformation"; + return "mavsdk.rpc.camera_server.SubscribeFormatStorageRequest"; } protected: - explicit StorageInformation(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -6149,145 +6110,9 @@ class StorageInformation final : // nested types ---------------------------------------------------- - using StorageStatus = StorageInformation_StorageStatus; - static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; - static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; - static constexpr StorageStatus STORAGE_STATUS_FORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; - static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; - static inline bool StorageStatus_IsValid(int value) { - return StorageInformation_StorageStatus_IsValid(value); - } - static constexpr StorageStatus StorageStatus_MIN = StorageInformation_StorageStatus_StorageStatus_MIN; - static constexpr StorageStatus StorageStatus_MAX = StorageInformation_StorageStatus_StorageStatus_MAX; - static constexpr int StorageStatus_ARRAYSIZE = StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageStatus_descriptor() { - return StorageInformation_StorageStatus_descriptor(); - } - template - static inline const std::string& StorageStatus_Name(T value) { - return StorageInformation_StorageStatus_Name(value); - } - static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { - return StorageInformation_StorageStatus_Parse(name, value); - } - - using StorageType = StorageInformation_StorageType; - static constexpr StorageType STORAGE_TYPE_UNKNOWN = StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; - static constexpr StorageType STORAGE_TYPE_USB_STICK = StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; - static constexpr StorageType STORAGE_TYPE_SD = StorageInformation_StorageType_STORAGE_TYPE_SD; - static constexpr StorageType STORAGE_TYPE_MICROSD = StorageInformation_StorageType_STORAGE_TYPE_MICROSD; - static constexpr StorageType STORAGE_TYPE_HD = StorageInformation_StorageType_STORAGE_TYPE_HD; - static constexpr StorageType STORAGE_TYPE_OTHER = StorageInformation_StorageType_STORAGE_TYPE_OTHER; - static inline bool StorageType_IsValid(int value) { - return StorageInformation_StorageType_IsValid(value); - } - static constexpr StorageType StorageType_MIN = StorageInformation_StorageType_StorageType_MIN; - static constexpr StorageType StorageType_MAX = StorageInformation_StorageType_StorageType_MAX; - static constexpr int StorageType_ARRAYSIZE = StorageInformation_StorageType_StorageType_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageType_descriptor() { - return StorageInformation_StorageType_descriptor(); - } - template - static inline const std::string& StorageType_Name(T value) { - return StorageInformation_StorageType_Name(value); - } - static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { - return StorageInformation_StorageType_Parse(name, value); - } - // accessors ------------------------------------------------------- - enum : int { - kUsedStorageMibFieldNumber = 1, - kAvailableStorageMibFieldNumber = 2, - kTotalStorageMibFieldNumber = 3, - kStorageStatusFieldNumber = 4, - kStorageIdFieldNumber = 5, - kStorageTypeFieldNumber = 6, - kReadSpeedMibSFieldNumber = 7, - kWriteSpeedMibSFieldNumber = 8, - }; - // float used_storage_mib = 1; - void clear_used_storage_mib() ; - float used_storage_mib() const; - void set_used_storage_mib(float value); - - private: - float _internal_used_storage_mib() const; - void _internal_set_used_storage_mib(float value); - - public: - // float available_storage_mib = 2; - void clear_available_storage_mib() ; - float available_storage_mib() const; - void set_available_storage_mib(float value); - - private: - float _internal_available_storage_mib() const; - void _internal_set_available_storage_mib(float value); - - public: - // float total_storage_mib = 3; - void clear_total_storage_mib() ; - float total_storage_mib() const; - void set_total_storage_mib(float value); - - private: - float _internal_total_storage_mib() const; - void _internal_set_total_storage_mib(float value); - - public: - // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; - void clear_storage_status() ; - ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus storage_status() const; - void set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); - - private: - ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus _internal_storage_status() const; - void _internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); - - public: - // uint32 storage_id = 5; - void clear_storage_id() ; - ::uint32_t storage_id() const; - void set_storage_id(::uint32_t value); - - private: - ::uint32_t _internal_storage_id() const; - void _internal_set_storage_id(::uint32_t value); - - public: - // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; - void clear_storage_type() ; - ::mavsdk::rpc::camera_server::StorageInformation_StorageType storage_type() const; - void set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); - - private: - ::mavsdk::rpc::camera_server::StorageInformation_StorageType _internal_storage_type() const; - void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); - - public: - // float read_speed_mib_s = 7; - void clear_read_speed_mib_s() ; - float read_speed_mib_s() const; - void set_read_speed_mib_s(float value); - - private: - float _internal_read_speed_mib_s() const; - void _internal_set_read_speed_mib_s(float value); - - public: - // float write_speed_mib_s = 8; - void clear_write_speed_mib_s() ; - float write_speed_mib_s() const; - void set_write_speed_mib_s(float value); - - private: - float _internal_write_speed_mib_s() const; - void _internal_set_write_speed_mib_s(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeFormatStorageRequest) private: class _Internal; @@ -6295,39 +6120,29 @@ class StorageInformation final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - float used_storage_mib_; - float available_storage_mib_; - float total_storage_mib_; - int storage_status_; - ::uint32_t storage_id_; - int storage_type_; - float read_speed_mib_s_; - float write_speed_mib_s_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- -class CaptureStatus final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatus) */ { +class FormatStorageResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.FormatStorageResponse) */ { public: - inline CaptureStatus() : CaptureStatus(nullptr) {} - ~CaptureStatus() override; + inline FormatStorageResponse() : FormatStorageResponse(nullptr) {} + ~FormatStorageResponse() override; template - explicit PROTOBUF_CONSTEXPR CaptureStatus(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CaptureStatus(const CaptureStatus& from); - CaptureStatus(CaptureStatus&& from) noexcept - : CaptureStatus() { + FormatStorageResponse(const FormatStorageResponse& from); + FormatStorageResponse(FormatStorageResponse&& from) noexcept + : FormatStorageResponse() { *this = ::std::move(from); } - inline CaptureStatus& operator=(const CaptureStatus& from) { + inline FormatStorageResponse& operator=(const FormatStorageResponse& from) { CopyFrom(from); return *this; } - inline CaptureStatus& operator=(CaptureStatus&& from) noexcept { + inline FormatStorageResponse& operator=(FormatStorageResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6357,20 +6172,20 @@ class CaptureStatus final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CaptureStatus& default_instance() { + static const FormatStorageResponse& default_instance() { return *internal_default_instance(); } - static inline const CaptureStatus* internal_default_instance() { - return reinterpret_cast( - &_CaptureStatus_default_instance_); + static inline const FormatStorageResponse* internal_default_instance() { + return reinterpret_cast( + &_FormatStorageResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 36; + 37; - friend void swap(CaptureStatus& a, CaptureStatus& b) { + friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { a.Swap(&b); } - inline void Swap(CaptureStatus* other) { + inline void Swap(FormatStorageResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -6383,7 +6198,7 @@ class CaptureStatus final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CaptureStatus* other) { + void UnsafeArenaSwap(FormatStorageResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -6391,14 +6206,14 @@ class CaptureStatus final : // implements Message ---------------------------------------------- - CaptureStatus* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FormatStorageResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CaptureStatus& from); + void CopyFrom(const FormatStorageResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CaptureStatus& from) { - CaptureStatus::MergeImpl(*this, from); + void MergeFrom( const FormatStorageResponse& from) { + FormatStorageResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -6416,15 +6231,15 @@ class CaptureStatus final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(CaptureStatus* other); + void InternalSwap(FormatStorageResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera_server.CaptureStatus"; + return "mavsdk.rpc.camera_server.FormatStorageResponse"; } protected: - explicit CaptureStatus(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit FormatStorageResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -6434,190 +6249,3253 @@ class CaptureStatus final : // nested types ---------------------------------------------------- - using ImageStatus = CaptureStatus_ImageStatus; - static constexpr ImageStatus IMAGE_STATUS_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; - static constexpr ImageStatus IMAGE_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; - static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; - static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; - static inline bool ImageStatus_IsValid(int value) { - return CaptureStatus_ImageStatus_IsValid(value); - } - static constexpr ImageStatus ImageStatus_MIN = CaptureStatus_ImageStatus_ImageStatus_MIN; - static constexpr ImageStatus ImageStatus_MAX = CaptureStatus_ImageStatus_ImageStatus_MAX; - static constexpr int ImageStatus_ARRAYSIZE = CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* ImageStatus_descriptor() { - return CaptureStatus_ImageStatus_descriptor(); - } - template - static inline const std::string& ImageStatus_Name(T value) { - return CaptureStatus_ImageStatus_Name(value); + // accessors ------------------------------------------------------- + + enum : int { + kStorageIdFieldNumber = 1, + }; + // int32 storage_id = 1; + void clear_storage_id() ; + ::int32_t storage_id() const; + void set_storage_id(::int32_t value); + + private: + ::int32_t _internal_storage_id() const; + void _internal_set_storage_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.FormatStorageResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t storage_id_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondFormatStorageRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageRequest) */ { + public: + inline RespondFormatStorageRequest() : RespondFormatStorageRequest(nullptr) {} + ~RespondFormatStorageRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondFormatStorageRequest(const RespondFormatStorageRequest& from); + RespondFormatStorageRequest(RespondFormatStorageRequest&& from) noexcept + : RespondFormatStorageRequest() { + *this = ::std::move(from); } - static inline bool ImageStatus_Parse(absl::string_view name, ImageStatus* value) { - return CaptureStatus_ImageStatus_Parse(name, value); + + inline RespondFormatStorageRequest& operator=(const RespondFormatStorageRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondFormatStorageRequest& operator=(RespondFormatStorageRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; } - using VideoStatus = CaptureStatus_VideoStatus; - static constexpr VideoStatus VIDEO_STATUS_IDLE = CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; - static constexpr VideoStatus VIDEO_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; - static inline bool VideoStatus_IsValid(int value) { - return CaptureStatus_VideoStatus_IsValid(value); + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); } - static constexpr VideoStatus VideoStatus_MIN = CaptureStatus_VideoStatus_VideoStatus_MIN; - static constexpr VideoStatus VideoStatus_MAX = CaptureStatus_VideoStatus_VideoStatus_MAX; - static constexpr int VideoStatus_ARRAYSIZE = CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* VideoStatus_descriptor() { - return CaptureStatus_VideoStatus_descriptor(); + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } - template - static inline const std::string& VideoStatus_Name(T value) { - return CaptureStatus_VideoStatus_Name(value); + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); } - static inline bool VideoStatus_Parse(absl::string_view name, VideoStatus* value) { - return CaptureStatus_VideoStatus_Parse(name, value); + 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 RespondFormatStorageRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondFormatStorageRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondFormatStorageRequest_default_instance_); } + static constexpr int kIndexInFileMessages = + 38; - // accessors ------------------------------------------------------- + friend void swap(RespondFormatStorageRequest& a, RespondFormatStorageRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondFormatStorageRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondFormatStorageRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } - enum : int { - kImageIntervalSFieldNumber = 1, - kRecordingTimeSFieldNumber = 2, - kAvailableCapacityMibFieldNumber = 3, - kImageStatusFieldNumber = 4, - kVideoStatusFieldNumber = 5, - kImageCountFieldNumber = 6, - }; - // float image_interval_s = 1; - void clear_image_interval_s() ; - float image_interval_s() const; - void set_image_interval_s(float value); + // implements Message ---------------------------------------------- + RespondFormatStorageRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondFormatStorageRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondFormatStorageRequest& from) { + RespondFormatStorageRequest::MergeImpl(*this, from); + } private: - float _internal_image_interval_s() const; - void _internal_set_image_interval_s(float value); - + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); public: - // float recording_time_s = 2; - void clear_recording_time_s() ; - float recording_time_s() const; - void set_recording_time_s(float value); + 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; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } private: - float _internal_recording_time_s() const; - void _internal_set_recording_time_s(float value); + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondFormatStorageRequest* other); + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondFormatStorageRequest"; + } + protected: + explicit RespondFormatStorageRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: - // float available_capacity_mib = 3; - void clear_available_capacity_mib() ; - float available_capacity_mib() const; - void set_available_capacity_mib(float value); + + 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 { + kFormatStorageFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; + void clear_format_storage_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback format_storage_feedback() const; + void set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); private: - float _internal_available_capacity_mib() const; - void _internal_set_available_capacity_mib(float value); + ::mavsdk::rpc::camera_server::CameraFeedback _internal_format_storage_feedback() const; + void _internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); public: - // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; - void clear_image_status() ; - ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus image_status() const; - void set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondFormatStorageRequest) + private: + class _Internal; - private: - ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus _internal_image_status() const; - void _internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + int format_storage_feedback_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondFormatStorageResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondFormatStorageResponse) */ { + public: + inline RespondFormatStorageResponse() : RespondFormatStorageResponse(nullptr) {} + ~RespondFormatStorageResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondFormatStorageResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondFormatStorageResponse(const RespondFormatStorageResponse& from); + RespondFormatStorageResponse(RespondFormatStorageResponse&& from) noexcept + : RespondFormatStorageResponse() { + *this = ::std::move(from); + } + + inline RespondFormatStorageResponse& operator=(const RespondFormatStorageResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondFormatStorageResponse& operator=(RespondFormatStorageResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondFormatStorageResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondFormatStorageResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondFormatStorageResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 39; + friend void swap(RespondFormatStorageResponse& a, RespondFormatStorageResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondFormatStorageResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondFormatStorageResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondFormatStorageResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondFormatStorageResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondFormatStorageResponse& from) { + RespondFormatStorageResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); public: - // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; - void clear_video_status() ; - ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus video_status() const; - void set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); + 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; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondFormatStorageResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondFormatStorageResponse"; + } + protected: + explicit RespondFormatStorageResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondFormatStorageResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeResetSettingsRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) */ { + public: + inline SubscribeResetSettingsRequest() : SubscribeResetSettingsRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeResetSettingsRequest(const SubscribeResetSettingsRequest& from); + SubscribeResetSettingsRequest(SubscribeResetSettingsRequest&& from) noexcept + : SubscribeResetSettingsRequest() { + *this = ::std::move(from); + } + + inline SubscribeResetSettingsRequest& operator=(const SubscribeResetSettingsRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeResetSettingsRequest& operator=(SubscribeResetSettingsRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeResetSettingsRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeResetSettingsRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 40; + + friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeResetSettingsRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeResetSettingsRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeResetSettingsRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeResetSettingsRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SubscribeResetSettingsRequest"; + } + protected: + explicit SubscribeResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SubscribeResetSettingsRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class ResetSettingsResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.ResetSettingsResponse) */ { + public: + inline ResetSettingsResponse() : ResetSettingsResponse(nullptr) {} + ~ResetSettingsResponse() override; + template + explicit PROTOBUF_CONSTEXPR ResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ResetSettingsResponse(const ResetSettingsResponse& from); + ResetSettingsResponse(ResetSettingsResponse&& from) noexcept + : ResetSettingsResponse() { + *this = ::std::move(from); + } + + inline ResetSettingsResponse& operator=(const ResetSettingsResponse& from) { + CopyFrom(from); + return *this; + } + inline ResetSettingsResponse& operator=(ResetSettingsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 ResetSettingsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 41; + + friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { + a.Swap(&b); + } + inline void Swap(ResetSettingsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ResetSettingsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ResetSettingsResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ResetSettingsResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const ResetSettingsResponse& from) { + ResetSettingsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ResetSettingsResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.ResetSettingsResponse"; + } + protected: + explicit ResetSettingsResponse(::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 { + kReservedFieldNumber = 1, + }; + // int32 reserved = 1; + void clear_reserved() ; + ::int32_t reserved() const; + void set_reserved(::int32_t value); + + private: + ::int32_t _internal_reserved() const; + void _internal_set_reserved(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.ResetSettingsResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::int32_t reserved_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondResetSettingsRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsRequest) */ { + public: + inline RespondResetSettingsRequest() : RespondResetSettingsRequest(nullptr) {} + ~RespondResetSettingsRequest() override; + template + explicit PROTOBUF_CONSTEXPR RespondResetSettingsRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondResetSettingsRequest(const RespondResetSettingsRequest& from); + RespondResetSettingsRequest(RespondResetSettingsRequest&& from) noexcept + : RespondResetSettingsRequest() { + *this = ::std::move(from); + } + + inline RespondResetSettingsRequest& operator=(const RespondResetSettingsRequest& from) { + CopyFrom(from); + return *this; + } + inline RespondResetSettingsRequest& operator=(RespondResetSettingsRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondResetSettingsRequest& default_instance() { + return *internal_default_instance(); + } + static inline const RespondResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_RespondResetSettingsRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 42; + + friend void swap(RespondResetSettingsRequest& a, RespondResetSettingsRequest& b) { + a.Swap(&b); + } + inline void Swap(RespondResetSettingsRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondResetSettingsRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondResetSettingsRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondResetSettingsRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondResetSettingsRequest& from) { + RespondResetSettingsRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondResetSettingsRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondResetSettingsRequest"; + } + protected: + explicit RespondResetSettingsRequest(::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 { + kResetSettingsFeedbackFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; + void clear_reset_settings_feedback() ; + ::mavsdk::rpc::camera_server::CameraFeedback reset_settings_feedback() const; + void set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + private: + ::mavsdk::rpc::camera_server::CameraFeedback _internal_reset_settings_feedback() const; + void _internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondResetSettingsRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + int reset_settings_feedback_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class RespondResetSettingsResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.RespondResetSettingsResponse) */ { + public: + inline RespondResetSettingsResponse() : RespondResetSettingsResponse(nullptr) {} + ~RespondResetSettingsResponse() override; + template + explicit PROTOBUF_CONSTEXPR RespondResetSettingsResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + RespondResetSettingsResponse(const RespondResetSettingsResponse& from); + RespondResetSettingsResponse(RespondResetSettingsResponse&& from) noexcept + : RespondResetSettingsResponse() { + *this = ::std::move(from); + } + + inline RespondResetSettingsResponse& operator=(const RespondResetSettingsResponse& from) { + CopyFrom(from); + return *this; + } + inline RespondResetSettingsResponse& operator=(RespondResetSettingsResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 RespondResetSettingsResponse& default_instance() { + return *internal_default_instance(); + } + static inline const RespondResetSettingsResponse* internal_default_instance() { + return reinterpret_cast( + &_RespondResetSettingsResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 43; + + friend void swap(RespondResetSettingsResponse& a, RespondResetSettingsResponse& b) { + a.Swap(&b); + } + inline void Swap(RespondResetSettingsResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(RespondResetSettingsResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + RespondResetSettingsResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const RespondResetSettingsResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const RespondResetSettingsResponse& from) { + RespondResetSettingsResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RespondResetSettingsResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.RespondResetSettingsResponse"; + } + protected: + explicit RespondResetSettingsResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.RespondResetSettingsResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Information final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Information) */ { + public: + inline Information() : Information(nullptr) {} + ~Information() override; + template + explicit PROTOBUF_CONSTEXPR Information(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Information(const Information& from); + Information(Information&& from) noexcept + : Information() { + *this = ::std::move(from); + } + + inline Information& operator=(const Information& from) { + CopyFrom(from); + return *this; + } + inline Information& operator=(Information&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Information& default_instance() { + return *internal_default_instance(); + } + static inline const Information* internal_default_instance() { + return reinterpret_cast( + &_Information_default_instance_); + } + static constexpr int kIndexInFileMessages = + 44; + + friend void swap(Information& a, Information& b) { + a.Swap(&b); + } + inline void Swap(Information* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Information* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Information* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Information& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Information& from) { + Information::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Information* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Information"; + } + protected: + explicit Information(::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 { + kVendorNameFieldNumber = 1, + kModelNameFieldNumber = 2, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, + }; + // string vendor_name = 1; + void clear_vendor_name() ; + const std::string& vendor_name() const; + + + + + template + void set_vendor_name(Arg_&& arg, Args_... args); + std::string* mutable_vendor_name(); + PROTOBUF_NODISCARD std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* ptr); + + private: + const std::string& _internal_vendor_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( + const std::string& value); + std::string* _internal_mutable_vendor_name(); + + public: + // string model_name = 2; + void clear_model_name() ; + const std::string& model_name() const; + + + + + template + void set_model_name(Arg_&& arg, Args_... args); + std::string* mutable_model_name(); + PROTOBUF_NODISCARD std::string* release_model_name(); + void set_allocated_model_name(std::string* ptr); + + private: + const std::string& _internal_model_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( + const std::string& value); + std::string* _internal_mutable_model_name(); + + public: + // string firmware_version = 3; + void clear_firmware_version() ; + const std::string& firmware_version() const; + + + + + template + void set_firmware_version(Arg_&& arg, Args_... args); + std::string* mutable_firmware_version(); + PROTOBUF_NODISCARD std::string* release_firmware_version(); + void set_allocated_firmware_version(std::string* ptr); + + private: + const std::string& _internal_firmware_version() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version( + const std::string& value); + std::string* _internal_mutable_firmware_version(); + + public: + // string definition_file_uri = 11; + void clear_definition_file_uri() ; + const std::string& definition_file_uri() const; + + + + + template + void set_definition_file_uri(Arg_&& arg, Args_... args); + std::string* mutable_definition_file_uri(); + PROTOBUF_NODISCARD std::string* release_definition_file_uri(); + void set_allocated_definition_file_uri(std::string* ptr); + + private: + const std::string& _internal_definition_file_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri( + const std::string& value); + std::string* _internal_mutable_definition_file_uri(); + + public: + // float focal_length_mm = 4; + void clear_focal_length_mm() ; + float focal_length_mm() const; + void set_focal_length_mm(float value); + + private: + float _internal_focal_length_mm() const; + void _internal_set_focal_length_mm(float value); + + public: + // float horizontal_sensor_size_mm = 5; + void clear_horizontal_sensor_size_mm() ; + float horizontal_sensor_size_mm() const; + void set_horizontal_sensor_size_mm(float value); + + private: + float _internal_horizontal_sensor_size_mm() const; + void _internal_set_horizontal_sensor_size_mm(float value); + + public: + // float vertical_sensor_size_mm = 6; + void clear_vertical_sensor_size_mm() ; + float vertical_sensor_size_mm() const; + void set_vertical_sensor_size_mm(float value); + + private: + float _internal_vertical_sensor_size_mm() const; + void _internal_set_vertical_sensor_size_mm(float value); + + public: + // uint32 horizontal_resolution_px = 7; + void clear_horizontal_resolution_px() ; + ::uint32_t horizontal_resolution_px() const; + void set_horizontal_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_horizontal_resolution_px() const; + void _internal_set_horizontal_resolution_px(::uint32_t value); + + public: + // uint32 vertical_resolution_px = 8; + void clear_vertical_resolution_px() ; + ::uint32_t vertical_resolution_px() const; + void set_vertical_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_vertical_resolution_px() const; + void _internal_set_vertical_resolution_px(::uint32_t value); + + public: + // uint32 lens_id = 9; + void clear_lens_id() ; + ::uint32_t lens_id() const; + void set_lens_id(::uint32_t value); + + private: + ::uint32_t _internal_lens_id() const; + void _internal_set_lens_id(::uint32_t value); + + public: + // uint32 definition_file_version = 10; + void clear_definition_file_version() ; + ::uint32_t definition_file_version() const; + void set_definition_file_version(::uint32_t value); + + private: + ::uint32_t _internal_definition_file_version() const; + void _internal_set_definition_file_version(::uint32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; + float focal_length_mm_; + float horizontal_sensor_size_mm_; + float vertical_sensor_size_mm_; + ::uint32_t horizontal_resolution_px_; + ::uint32_t vertical_resolution_px_; + ::uint32_t lens_id_; + ::uint32_t definition_file_version_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Position final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Position) */ { + public: + inline Position() : Position(nullptr) {} + ~Position() override; + template + explicit PROTOBUF_CONSTEXPR Position(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Position(const Position& from); + Position(Position&& from) noexcept + : Position() { + *this = ::std::move(from); + } + + inline Position& operator=(const Position& from) { + CopyFrom(from); + return *this; + } + inline Position& operator=(Position&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Position& default_instance() { + return *internal_default_instance(); + } + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); + } + static constexpr int kIndexInFileMessages = + 45; + + friend void swap(Position& a, Position& b) { + a.Swap(&b); + } + inline void Swap(Position* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Position* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Position* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Position& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Position& from) { + Position::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Position* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Position"; + } + protected: + explicit Position(::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 { + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 4, + }; + // double latitude_deg = 1; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); + + private: + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); + + public: + // double longitude_deg = 2; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); + + private: + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); + + public: + // float absolute_altitude_m = 3; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + private: + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); + + public: + // float relative_altitude_m = 4; + void clear_relative_altitude_m() ; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); + + private: + float _internal_relative_altitude_m() const; + void _internal_set_relative_altitude_m(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Position) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class Quaternion final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.Quaternion) */ { + public: + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; + template + explicit PROTOBUF_CONSTEXPR Quaternion(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + Quaternion(const Quaternion& from); + Quaternion(Quaternion&& from) noexcept + : Quaternion() { + *this = ::std::move(from); + } + + inline Quaternion& operator=(const Quaternion& from) { + CopyFrom(from); + return *this; + } + inline Quaternion& operator=(Quaternion&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 Quaternion& default_instance() { + return *internal_default_instance(); + } + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); + } + static constexpr int kIndexInFileMessages = + 46; + + friend void swap(Quaternion& a, Quaternion& b) { + a.Swap(&b); + } + inline void Swap(Quaternion* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Quaternion* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Quaternion* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const Quaternion& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const Quaternion& from) { + Quaternion::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Quaternion* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.Quaternion"; + } + protected: + explicit Quaternion(::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 { + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 4, + }; + // float w = 1; + void clear_w() ; + float w() const; + void set_w(float value); + + private: + float _internal_w() const; + void _internal_set_w(float value); + + public: + // float x = 2; + void clear_x() ; + float x() const; + void set_x(float value); + + private: + float _internal_x() const; + void _internal_set_x(float value); + + public: + // float y = 3; + void clear_y() ; + float y() const; + void set_y(float value); + + private: + float _internal_y() const; + void _internal_set_y(float value); + + public: + // float z = 4; + void clear_z() ; + float z() const; + void set_z(float value); + + private: + float _internal_z() const; + void _internal_set_z(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Quaternion) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + float w_; + float x_; + float y_; + float z_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CaptureInfo final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureInfo) */ { + public: + inline CaptureInfo() : CaptureInfo(nullptr) {} + ~CaptureInfo() override; + template + explicit PROTOBUF_CONSTEXPR CaptureInfo(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CaptureInfo(const CaptureInfo& from); + CaptureInfo(CaptureInfo&& from) noexcept + : CaptureInfo() { + *this = ::std::move(from); + } + + inline CaptureInfo& operator=(const CaptureInfo& from) { + CopyFrom(from); + return *this; + } + inline CaptureInfo& operator=(CaptureInfo&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CaptureInfo& default_instance() { + return *internal_default_instance(); + } + static inline const CaptureInfo* internal_default_instance() { + return reinterpret_cast( + &_CaptureInfo_default_instance_); + } + static constexpr int kIndexInFileMessages = + 47; + + friend void swap(CaptureInfo& a, CaptureInfo& b) { + a.Swap(&b); + } + inline void Swap(CaptureInfo* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CaptureInfo* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CaptureInfo* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CaptureInfo& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const CaptureInfo& from) { + CaptureInfo::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CaptureInfo* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.CaptureInfo"; + } + protected: + explicit CaptureInfo(::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 { + kFileUrlFieldNumber = 6, + kPositionFieldNumber = 1, + kAttitudeQuaternionFieldNumber = 2, + kTimeUtcUsFieldNumber = 3, + kIsSuccessFieldNumber = 4, + kIndexFieldNumber = 5, + }; + // string file_url = 6; + void clear_file_url() ; + const std::string& file_url() const; + + + + + template + void set_file_url(Arg_&& arg, Args_... args); + std::string* mutable_file_url(); + PROTOBUF_NODISCARD std::string* release_file_url(); + void set_allocated_file_url(std::string* ptr); + + private: + const std::string& _internal_file_url() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_file_url( + const std::string& value); + std::string* _internal_mutable_file_url(); + + public: + // .mavsdk.rpc.camera_server.Position position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::camera_server::Position& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Position* release_position(); + ::mavsdk::rpc::camera_server::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::camera_server::Position* position); + private: + const ::mavsdk::rpc::camera_server::Position& _internal_position() const; + ::mavsdk::rpc::camera_server::Position* _internal_mutable_position(); + public: + void unsafe_arena_set_allocated_position( + ::mavsdk::rpc::camera_server::Position* position); + ::mavsdk::rpc::camera_server::Position* unsafe_arena_release_position(); + // .mavsdk.rpc.camera_server.Quaternion attitude_quaternion = 2; + bool has_attitude_quaternion() const; + void clear_attitude_quaternion() ; + const ::mavsdk::rpc::camera_server::Quaternion& attitude_quaternion() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::Quaternion* release_attitude_quaternion(); + ::mavsdk::rpc::camera_server::Quaternion* mutable_attitude_quaternion(); + void set_allocated_attitude_quaternion(::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + private: + const ::mavsdk::rpc::camera_server::Quaternion& _internal_attitude_quaternion() const; + ::mavsdk::rpc::camera_server::Quaternion* _internal_mutable_attitude_quaternion(); + public: + void unsafe_arena_set_allocated_attitude_quaternion( + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion); + ::mavsdk::rpc::camera_server::Quaternion* unsafe_arena_release_attitude_quaternion(); + // uint64 time_utc_us = 3; + void clear_time_utc_us() ; + ::uint64_t time_utc_us() const; + void set_time_utc_us(::uint64_t value); + + private: + ::uint64_t _internal_time_utc_us() const; + void _internal_set_time_utc_us(::uint64_t value); + + public: + // bool is_success = 4; + void clear_is_success() ; + bool is_success() const; + void set_is_success(bool value); + + private: + bool _internal_is_success() const; + void _internal_set_is_success(bool value); + + public: + // int32 index = 5; + void clear_index() ; + ::int32_t index() const; + void set_index(::int32_t value); + + private: + ::int32_t _internal_index() const; + void _internal_set_index(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureInfo) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr file_url_; + ::mavsdk::rpc::camera_server::Position* position_; + ::mavsdk::rpc::camera_server::Quaternion* attitude_quaternion_; + ::uint64_t time_utc_us_; + bool is_success_; + ::int32_t index_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CameraServerResult final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CameraServerResult) */ { + public: + inline CameraServerResult() : CameraServerResult(nullptr) {} + ~CameraServerResult() override; + template + explicit PROTOBUF_CONSTEXPR CameraServerResult(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CameraServerResult(const CameraServerResult& from); + CameraServerResult(CameraServerResult&& from) noexcept + : CameraServerResult() { + *this = ::std::move(from); + } + + inline CameraServerResult& operator=(const CameraServerResult& from) { + CopyFrom(from); + return *this; + } + inline CameraServerResult& operator=(CameraServerResult&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CameraServerResult& default_instance() { + return *internal_default_instance(); + } + static inline const CameraServerResult* internal_default_instance() { + return reinterpret_cast( + &_CameraServerResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 48; + + friend void swap(CameraServerResult& a, CameraServerResult& b) { + a.Swap(&b); + } + inline void Swap(CameraServerResult* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CameraServerResult* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CameraServerResult* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CameraServerResult& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const CameraServerResult& from) { + CameraServerResult::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CameraServerResult* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.CameraServerResult"; + } + protected: + explicit CameraServerResult(::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 ---------------------------------------------------- + + using Result = CameraServerResult_Result; + static constexpr Result RESULT_UNKNOWN = CameraServerResult_Result_RESULT_UNKNOWN; + static constexpr Result RESULT_SUCCESS = CameraServerResult_Result_RESULT_SUCCESS; + static constexpr Result RESULT_IN_PROGRESS = CameraServerResult_Result_RESULT_IN_PROGRESS; + static constexpr Result RESULT_BUSY = CameraServerResult_Result_RESULT_BUSY; + static constexpr Result RESULT_DENIED = CameraServerResult_Result_RESULT_DENIED; + static constexpr Result RESULT_ERROR = CameraServerResult_Result_RESULT_ERROR; + static constexpr Result RESULT_TIMEOUT = CameraServerResult_Result_RESULT_TIMEOUT; + static constexpr Result RESULT_WRONG_ARGUMENT = CameraServerResult_Result_RESULT_WRONG_ARGUMENT; + static constexpr Result RESULT_NO_SYSTEM = CameraServerResult_Result_RESULT_NO_SYSTEM; + static inline bool Result_IsValid(int value) { + return CameraServerResult_Result_IsValid(value); + } + static constexpr Result Result_MIN = CameraServerResult_Result_Result_MIN; + static constexpr Result Result_MAX = CameraServerResult_Result_Result_MAX; + static constexpr int Result_ARRAYSIZE = CameraServerResult_Result_Result_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* Result_descriptor() { + return CameraServerResult_Result_descriptor(); + } + template + static inline const std::string& Result_Name(T value) { + return CameraServerResult_Result_Name(value); + } + static inline bool Result_Parse(absl::string_view name, Result* value) { + return CameraServerResult_Result_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kResultStrFieldNumber = 2, + kResultFieldNumber = 1, + }; + // string result_str = 2; + void clear_result_str() ; + const std::string& result_str() const; + + + + + template + void set_result_str(Arg_&& arg, Args_... args); + std::string* mutable_result_str(); + PROTOBUF_NODISCARD std::string* release_result_str(); + void set_allocated_result_str(std::string* ptr); + + 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.camera_server.CameraServerResult.Result result = 1; + void clear_result() ; + ::mavsdk::rpc::camera_server::CameraServerResult_Result result() const; + void set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + + private: + ::mavsdk::rpc::camera_server::CameraServerResult_Result _internal_result() const; + void _internal_set_result(::mavsdk::rpc::camera_server::CameraServerResult_Result value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CameraServerResult) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr result_str_; + int result_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class StorageInformation final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.StorageInformation) */ { + public: + inline StorageInformation() : StorageInformation(nullptr) {} + ~StorageInformation() override; + template + explicit PROTOBUF_CONSTEXPR StorageInformation(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + StorageInformation(const StorageInformation& from); + StorageInformation(StorageInformation&& from) noexcept + : StorageInformation() { + *this = ::std::move(from); + } + + inline StorageInformation& operator=(const StorageInformation& from) { + CopyFrom(from); + return *this; + } + inline StorageInformation& operator=(StorageInformation&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 StorageInformation& default_instance() { + return *internal_default_instance(); + } + static inline const StorageInformation* internal_default_instance() { + return reinterpret_cast( + &_StorageInformation_default_instance_); + } + static constexpr int kIndexInFileMessages = + 49; + + friend void swap(StorageInformation& a, StorageInformation& b) { + a.Swap(&b); + } + inline void Swap(StorageInformation* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(StorageInformation* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + StorageInformation* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const StorageInformation& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const StorageInformation& from) { + StorageInformation::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StorageInformation* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.StorageInformation"; + } + protected: + explicit StorageInformation(::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 ---------------------------------------------------- + + using StorageStatus = StorageInformation_StorageStatus; + static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; + static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_UNFORMATTED; + static constexpr StorageStatus STORAGE_STATUS_FORMATTED = StorageInformation_StorageStatus_STORAGE_STATUS_FORMATTED; + static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = StorageInformation_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; + static inline bool StorageStatus_IsValid(int value) { + return StorageInformation_StorageStatus_IsValid(value); + } + static constexpr StorageStatus StorageStatus_MIN = StorageInformation_StorageStatus_StorageStatus_MIN; + static constexpr StorageStatus StorageStatus_MAX = StorageInformation_StorageStatus_StorageStatus_MAX; + static constexpr int StorageStatus_ARRAYSIZE = StorageInformation_StorageStatus_StorageStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageStatus_descriptor() { + return StorageInformation_StorageStatus_descriptor(); + } + template + static inline const std::string& StorageStatus_Name(T value) { + return StorageInformation_StorageStatus_Name(value); + } + static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { + return StorageInformation_StorageStatus_Parse(name, value); + } + + using StorageType = StorageInformation_StorageType; + static constexpr StorageType STORAGE_TYPE_UNKNOWN = StorageInformation_StorageType_STORAGE_TYPE_UNKNOWN; + static constexpr StorageType STORAGE_TYPE_USB_STICK = StorageInformation_StorageType_STORAGE_TYPE_USB_STICK; + static constexpr StorageType STORAGE_TYPE_SD = StorageInformation_StorageType_STORAGE_TYPE_SD; + static constexpr StorageType STORAGE_TYPE_MICROSD = StorageInformation_StorageType_STORAGE_TYPE_MICROSD; + static constexpr StorageType STORAGE_TYPE_HD = StorageInformation_StorageType_STORAGE_TYPE_HD; + static constexpr StorageType STORAGE_TYPE_OTHER = StorageInformation_StorageType_STORAGE_TYPE_OTHER; + static inline bool StorageType_IsValid(int value) { + return StorageInformation_StorageType_IsValid(value); + } + static constexpr StorageType StorageType_MIN = StorageInformation_StorageType_StorageType_MIN; + static constexpr StorageType StorageType_MAX = StorageInformation_StorageType_StorageType_MAX; + static constexpr int StorageType_ARRAYSIZE = StorageInformation_StorageType_StorageType_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* StorageType_descriptor() { + return StorageInformation_StorageType_descriptor(); + } + template + static inline const std::string& StorageType_Name(T value) { + return StorageInformation_StorageType_Name(value); + } + static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { + return StorageInformation_StorageType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kUsedStorageMibFieldNumber = 1, + kAvailableStorageMibFieldNumber = 2, + kTotalStorageMibFieldNumber = 3, + kStorageStatusFieldNumber = 4, + kStorageIdFieldNumber = 5, + kStorageTypeFieldNumber = 6, + kReadSpeedMibSFieldNumber = 7, + kWriteSpeedMibSFieldNumber = 8, + }; + // float used_storage_mib = 1; + void clear_used_storage_mib() ; + float used_storage_mib() const; + void set_used_storage_mib(float value); + + private: + float _internal_used_storage_mib() const; + void _internal_set_used_storage_mib(float value); + + public: + // float available_storage_mib = 2; + void clear_available_storage_mib() ; + float available_storage_mib() const; + void set_available_storage_mib(float value); + + private: + float _internal_available_storage_mib() const; + void _internal_set_available_storage_mib(float value); + + public: + // float total_storage_mib = 3; + void clear_total_storage_mib() ; + float total_storage_mib() const; + void set_total_storage_mib(float value); + + private: + float _internal_total_storage_mib() const; + void _internal_set_total_storage_mib(float value); + + public: + // .mavsdk.rpc.camera_server.StorageInformation.StorageStatus storage_status = 4; + void clear_storage_status() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus storage_status() const; + void set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + + private: + ::mavsdk::rpc::camera_server::StorageInformation_StorageStatus _internal_storage_status() const; + void _internal_set_storage_status(::mavsdk::rpc::camera_server::StorageInformation_StorageStatus value); + + public: + // uint32 storage_id = 5; + void clear_storage_id() ; + ::uint32_t storage_id() const; + void set_storage_id(::uint32_t value); + + private: + ::uint32_t _internal_storage_id() const; + void _internal_set_storage_id(::uint32_t value); + + public: + // .mavsdk.rpc.camera_server.StorageInformation.StorageType storage_type = 6; + void clear_storage_type() ; + ::mavsdk::rpc::camera_server::StorageInformation_StorageType storage_type() const; + void set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); + + private: + ::mavsdk::rpc::camera_server::StorageInformation_StorageType _internal_storage_type() const; + void _internal_set_storage_type(::mavsdk::rpc::camera_server::StorageInformation_StorageType value); + + public: + // float read_speed_mib_s = 7; + void clear_read_speed_mib_s() ; + float read_speed_mib_s() const; + void set_read_speed_mib_s(float value); + + private: + float _internal_read_speed_mib_s() const; + void _internal_set_read_speed_mib_s(float value); + + public: + // float write_speed_mib_s = 8; + void clear_write_speed_mib_s() ; + float write_speed_mib_s() const; + void set_write_speed_mib_s(float value); + + private: + float _internal_write_speed_mib_s() const; + void _internal_set_write_speed_mib_s(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.StorageInformation) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + float used_storage_mib_; + float available_storage_mib_; + float total_storage_mib_; + int storage_status_; + ::uint32_t storage_id_; + int storage_type_; + float read_speed_mib_s_; + float write_speed_mib_s_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CaptureStatus final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.CaptureStatus) */ { + public: + inline CaptureStatus() : CaptureStatus(nullptr) {} + ~CaptureStatus() override; + template + explicit PROTOBUF_CONSTEXPR CaptureStatus(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CaptureStatus(const CaptureStatus& from); + CaptureStatus(CaptureStatus&& from) noexcept + : CaptureStatus() { + *this = ::std::move(from); + } + + inline CaptureStatus& operator=(const CaptureStatus& from) { + CopyFrom(from); + return *this; + } + inline CaptureStatus& operator=(CaptureStatus&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CaptureStatus& default_instance() { + return *internal_default_instance(); + } + static inline const CaptureStatus* internal_default_instance() { + return reinterpret_cast( + &_CaptureStatus_default_instance_); + } + static constexpr int kIndexInFileMessages = + 50; + + friend void swap(CaptureStatus& a, CaptureStatus& b) { + a.Swap(&b); + } + inline void Swap(CaptureStatus* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CaptureStatus* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CaptureStatus* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CaptureStatus& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const CaptureStatus& from) { + CaptureStatus::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CaptureStatus* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.CaptureStatus"; + } + protected: + explicit CaptureStatus(::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 ---------------------------------------------------- + + using ImageStatus = CaptureStatus_ImageStatus; + static constexpr ImageStatus IMAGE_STATUS_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_IDLE; + static constexpr ImageStatus IMAGE_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_CAPTURE_IN_PROGRESS; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IDLE = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IDLE; + static constexpr ImageStatus IMAGE_STATUS_INTERVAL_IN_PROGRESS = CaptureStatus_ImageStatus_IMAGE_STATUS_INTERVAL_IN_PROGRESS; + static inline bool ImageStatus_IsValid(int value) { + return CaptureStatus_ImageStatus_IsValid(value); + } + static constexpr ImageStatus ImageStatus_MIN = CaptureStatus_ImageStatus_ImageStatus_MIN; + static constexpr ImageStatus ImageStatus_MAX = CaptureStatus_ImageStatus_ImageStatus_MAX; + static constexpr int ImageStatus_ARRAYSIZE = CaptureStatus_ImageStatus_ImageStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* ImageStatus_descriptor() { + return CaptureStatus_ImageStatus_descriptor(); + } + template + static inline const std::string& ImageStatus_Name(T value) { + return CaptureStatus_ImageStatus_Name(value); + } + static inline bool ImageStatus_Parse(absl::string_view name, ImageStatus* value) { + return CaptureStatus_ImageStatus_Parse(name, value); + } + + using VideoStatus = CaptureStatus_VideoStatus; + static constexpr VideoStatus VIDEO_STATUS_IDLE = CaptureStatus_VideoStatus_VIDEO_STATUS_IDLE; + static constexpr VideoStatus VIDEO_STATUS_CAPTURE_IN_PROGRESS = CaptureStatus_VideoStatus_VIDEO_STATUS_CAPTURE_IN_PROGRESS; + static inline bool VideoStatus_IsValid(int value) { + return CaptureStatus_VideoStatus_IsValid(value); + } + static constexpr VideoStatus VideoStatus_MIN = CaptureStatus_VideoStatus_VideoStatus_MIN; + static constexpr VideoStatus VideoStatus_MAX = CaptureStatus_VideoStatus_VideoStatus_MAX; + static constexpr int VideoStatus_ARRAYSIZE = CaptureStatus_VideoStatus_VideoStatus_ARRAYSIZE; + static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* VideoStatus_descriptor() { + return CaptureStatus_VideoStatus_descriptor(); + } + template + static inline const std::string& VideoStatus_Name(T value) { + return CaptureStatus_VideoStatus_Name(value); + } + static inline bool VideoStatus_Parse(absl::string_view name, VideoStatus* value) { + return CaptureStatus_VideoStatus_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + enum : int { + kImageIntervalSFieldNumber = 1, + kRecordingTimeSFieldNumber = 2, + kAvailableCapacityMibFieldNumber = 3, + kImageStatusFieldNumber = 4, + kVideoStatusFieldNumber = 5, + kImageCountFieldNumber = 6, + }; + // float image_interval_s = 1; + void clear_image_interval_s() ; + float image_interval_s() const; + void set_image_interval_s(float value); + + private: + float _internal_image_interval_s() const; + void _internal_set_image_interval_s(float value); + + public: + // float recording_time_s = 2; + void clear_recording_time_s() ; + float recording_time_s() const; + void set_recording_time_s(float value); + + private: + float _internal_recording_time_s() const; + void _internal_set_recording_time_s(float value); + + public: + // float available_capacity_mib = 3; + void clear_available_capacity_mib() ; + float available_capacity_mib() const; + void set_available_capacity_mib(float value); + + private: + float _internal_available_capacity_mib() const; + void _internal_set_available_capacity_mib(float value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.ImageStatus image_status = 4; + void clear_image_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus image_status() const; + void set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + private: + ::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus _internal_image_status() const; + void _internal_set_image_status(::mavsdk::rpc::camera_server::CaptureStatus_ImageStatus value); + + public: + // .mavsdk.rpc.camera_server.CaptureStatus.VideoStatus video_status = 5; + void clear_video_status() ; + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus video_status() const; + void set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); + + private: + ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus _internal_video_status() const; + void _internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); + + public: + // int32 image_count = 6; + void clear_image_count() ; + ::int32_t image_count() const; + void set_image_count(::int32_t value); + + private: + ::int32_t _internal_image_count() const; + void _internal_set_image_count(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatus) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + float image_interval_s_; + float recording_time_s_; + float available_capacity_mib_; + int image_status_; + int video_status_; + ::int32_t image_count_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// SetInformationRequest + +// .mavsdk.rpc.camera_server.Information information = 1; +inline bool SetInformationRequest::has_information() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.information_ != nullptr); + return value; +} +inline void SetInformationRequest::clear_information() { + if (_impl_.information_ != nullptr) _impl_.information_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::_internal_information() const { + const ::mavsdk::rpc::camera_server::Information* p = _impl_.information_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_Information_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::information() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationRequest.information) + return _internal_information(); +} +inline void SetInformationRequest::unsafe_arena_set_allocated_information( + ::mavsdk::rpc::camera_server::Information* information) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.information_); + } + _impl_.information_ = information; + if (information) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release_information() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; + _impl_.information_ = 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::camera_server::Information* SetInformationRequest::unsafe_arena_release_information() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationRequest.information) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; + _impl_.information_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::_internal_mutable_information() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.information_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(GetArenaForAllocation()); + _impl_.information_ = p; + } + return _impl_.information_; +} +inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::mutable_information() { + ::mavsdk::rpc::camera_server::Information* _msg = _internal_mutable_information(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationRequest.information) + return _msg; +} +inline void SetInformationRequest::set_allocated_information(::mavsdk::rpc::camera_server::Information* information) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.information_; + } + if (information) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(information); + if (message_arena != submessage_arena) { + information = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, information, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.information_ = information; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) +} + +// ------------------------------------------------------------------- + +// SetInformationResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetInformationResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void SetInformationResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInformationResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInformationResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void SetInformationResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* SetInformationResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + return _msg; +} +inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SetInProgressRequest + +// bool in_progress = 1; +inline void SetInProgressRequest::clear_in_progress() { + _impl_.in_progress_ = false; +} +inline bool SetInProgressRequest::in_progress() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) + return _internal_in_progress(); +} +inline void SetInProgressRequest::set_in_progress(bool value) { + _internal_set_in_progress(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) +} +inline bool SetInProgressRequest::_internal_in_progress() const { + return _impl_.in_progress_; +} +inline void SetInProgressRequest::_internal_set_in_progress(bool value) { + ; + _impl_.in_progress_ = value; +} + +// ------------------------------------------------------------------- + +// SetInProgressResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetInProgressResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void SetInProgressResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* SetInProgressResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + return _msg; +} +inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SubscribeTakePhotoRequest + +// ------------------------------------------------------------------- + +// TakePhotoResponse + +// int32 index = 1; +inline void TakePhotoResponse::clear_index() { + _impl_.index_ = 0; +} +inline ::int32_t TakePhotoResponse::index() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.index) + return _internal_index(); +} +inline void TakePhotoResponse::set_index(::int32_t value) { + _internal_set_index(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.TakePhotoResponse.index) +} +inline ::int32_t TakePhotoResponse::_internal_index() const { + return _impl_.index_; +} +inline void TakePhotoResponse::_internal_set_index(::int32_t value) { + ; + _impl_.index_ = value; +} + +// ------------------------------------------------------------------- + +// RespondTakePhotoRequest + +// .mavsdk.rpc.camera_server.CameraFeedback take_photo_feedback = 1; +inline void RespondTakePhotoRequest::clear_take_photo_feedback() { + _impl_.take_photo_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::take_photo_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) + return _internal_take_photo_feedback(); +} +inline void RespondTakePhotoRequest::set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_take_photo_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondTakePhotoRequest::_internal_take_photo_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.take_photo_feedback_); +} +inline void RespondTakePhotoRequest::_internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.take_photo_feedback_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; +inline bool RespondTakePhotoRequest::has_capture_info() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.capture_info_ != nullptr); + return value; +} +inline void RespondTakePhotoRequest::clear_capture_info() { + if (_impl_.capture_info_ != nullptr) _impl_.capture_info_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::_internal_capture_info() const { + const ::mavsdk::rpc::camera_server::CaptureInfo* p = _impl_.capture_info_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::capture_info() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + return _internal_capture_info(); +} +inline void RespondTakePhotoRequest::unsafe_arena_set_allocated_capture_info( + ::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.capture_info_); + } + _impl_.capture_info_ = capture_info; + if (capture_info) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::release_capture_info() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; + _impl_.capture_info_ = 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::camera_server::CaptureInfo* RespondTakePhotoRequest::unsafe_arena_release_capture_info() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; + _impl_.capture_info_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::_internal_mutable_capture_info() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.capture_info_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArenaForAllocation()); + _impl_.capture_info_ = p; + } + return _impl_.capture_info_; +} +inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::mutable_capture_info() { + ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + return _msg; +} +inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.capture_info_; + } + if (capture_info) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(capture_info); + if (message_arena != submessage_arena) { + capture_info = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, capture_info, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.capture_info_ = capture_info; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) +} - private: - ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus _internal_video_status() const; - void _internal_set_video_status(::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus value); +// ------------------------------------------------------------------- - public: - // int32 image_count = 6; - void clear_image_count() ; - ::int32_t image_count() const; - void set_image_count(::int32_t value); +// RespondTakePhotoResponse - private: - ::int32_t _internal_image_count() const; - void _internal_set_image_count(::int32_t value); +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondTakePhotoResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void RespondTakePhotoResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* RespondTakePhotoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + return _msg; +} +inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) +} - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.CaptureStatus) - private: - class _Internal; +// ------------------------------------------------------------------- - template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; - typedef void InternalArenaConstructable_; - typedef void DestructorSkippable_; - struct Impl_ { - float image_interval_s_; - float recording_time_s_; - float available_capacity_mib_; - int image_status_; - int video_status_; - ::int32_t image_count_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; -}; +// SubscribeStartVideoRequest -// =================================================================== +// ------------------------------------------------------------------- +// StartVideoResponse +// int32 stream_id = 1; +inline void StartVideoResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StartVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) + return _internal_stream_id(); +} +inline void StartVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) +} +inline ::int32_t StartVideoResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; +} +// ------------------------------------------------------------------- -// =================================================================== +// RespondStartVideoRequest +// .mavsdk.rpc.camera_server.CameraFeedback start_video_feedback = 1; +inline void RespondStartVideoRequest::clear_start_video_feedback() { + _impl_.start_video_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::start_video_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) + return _internal_start_video_feedback(); +} +inline void RespondStartVideoRequest::set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_start_video_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoRequest.start_video_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoRequest::_internal_start_video_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_feedback_); +} +inline void RespondStartVideoRequest::_internal_set_start_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.start_video_feedback_ = value; +} -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -#endif // __GNUC__ // ------------------------------------------------------------------- -// SetInformationRequest +// RespondStartVideoResponse -// .mavsdk.rpc.camera_server.Information information = 1; -inline bool SetInformationRequest::has_information() const { +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondStartVideoResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.information_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void SetInformationRequest::clear_information() { - if (_impl_.information_ != nullptr) _impl_.information_->Clear(); +inline void RespondStartVideoResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::_internal_information() const { - const ::mavsdk::rpc::camera_server::Information* p = _impl_.information_; - return p != nullptr ? *p : reinterpret_cast( - ::mavsdk::rpc::camera_server::_Information_default_instance_); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::Information& SetInformationRequest::information() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationRequest.information) - return _internal_information(); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void SetInformationRequest::unsafe_arena_set_allocated_information( - ::mavsdk::rpc::camera_server::Information* information) { +inline void RespondStartVideoResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { - delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.information_); + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); } - _impl_.information_ = information; - if (information) { + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release_information() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::release_camera_server_result() { _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; - _impl_.information_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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); @@ -6629,70 +9507,122 @@ inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::release #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::unsafe_arena_release_information() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationRequest.information) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::Information* temp = _impl_.information_; - _impl_.information_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::_internal_mutable_information() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::_internal_mutable_camera_server_result() { _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.information_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::Information>(GetArenaForAllocation()); - _impl_.information_ = p; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; } - return _impl_.information_; + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::Information* SetInformationRequest::mutable_information() { - ::mavsdk::rpc::camera_server::Information* _msg = _internal_mutable_information(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationRequest.information) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) return _msg; } -inline void SetInformationRequest::set_allocated_information(::mavsdk::rpc::camera_server::Information* information) { +inline void RespondStartVideoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { - delete _impl_.information_; + delete _impl_.camera_server_result_; } - if (information) { + if (camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = - ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(information); + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); if (message_arena != submessage_arena) { - information = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( - message_arena, information, submessage_arena); + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); } _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.information_ = information; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationRequest.information) + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + +// SubscribeStopVideoRequest + +// ------------------------------------------------------------------- + +// StopVideoResponse + +// int32 stream_id = 1; +inline void StopVideoResponse::clear_stream_id() { + _impl_.stream_id_ = 0; +} +inline ::int32_t StopVideoResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) + return _internal_stream_id(); +} +inline void StopVideoResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) +} +inline ::int32_t StopVideoResponse::_internal_stream_id() const { + return _impl_.stream_id_; +} +inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { + ; + _impl_.stream_id_ = value; } // ------------------------------------------------------------------- -// SetInformationResponse +// RespondStopVideoRequest + +// .mavsdk.rpc.camera_server.CameraFeedback stop_video_feedback = 1; +inline void RespondStopVideoRequest::clear_stop_video_feedback() { + _impl_.stop_video_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::stop_video_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) + return _internal_stop_video_feedback(); +} +inline void RespondStopVideoRequest::set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_stop_video_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoRequest.stop_video_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoRequest::_internal_stop_video_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_feedback_); +} +inline void RespondStopVideoRequest::_internal_set_stop_video_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.stop_video_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStopVideoResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetInformationResponse::has_camera_server_result() const { +inline bool RespondStopVideoResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void SetInformationResponse::clear_camera_server_result() { +inline void RespondStopVideoResponse::clear_camera_server_result() { if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInformationResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoResponse::_internal_camera_server_result() const { const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; return p != nullptr ? *p : reinterpret_cast( ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInformationResponse::camera_server_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) return _internal_camera_server_result(); } -inline void SetInformationResponse::unsafe_arena_set_allocated_camera_server_result( +inline void RespondStopVideoResponse::unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); @@ -6703,9 +9633,9 @@ inline void SetInformationResponse::unsafe_arena_set_allocated_camera_server_res } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::release_camera_server_result() { _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; @@ -6720,14 +9650,14 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::unsafe_arena_release_camera_server_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::_internal_mutable_camera_server_result() { _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); @@ -6735,12 +9665,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse: } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInformationResponse::mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoResponse::mutable_camera_server_result() { ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) return _msg; } -inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { +inline void RespondStopVideoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { delete _impl_.camera_server_result_; @@ -6757,57 +9687,85 @@ inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk: _impl_._has_bits_[0] &= ~0x00000001u; } _impl_.camera_server_result_ = camera_server_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInformationResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoResponse.camera_server_result) } // ------------------------------------------------------------------- -// SetInProgressRequest +// SubscribeStartVideoStreamingRequest -// bool in_progress = 1; -inline void SetInProgressRequest::clear_in_progress() { - _impl_.in_progress_ = false; +// ------------------------------------------------------------------- + +// StartVideoStreamingResponse + +// int32 stream_id = 1; +inline void StartVideoStreamingResponse::clear_stream_id() { + _impl_.stream_id_ = 0; } -inline bool SetInProgressRequest::in_progress() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) - return _internal_in_progress(); +inline ::int32_t StartVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) + return _internal_stream_id(); } -inline void SetInProgressRequest::set_in_progress(bool value) { - _internal_set_in_progress(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.SetInProgressRequest.in_progress) +inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { + _internal_set_stream_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) } -inline bool SetInProgressRequest::_internal_in_progress() const { - return _impl_.in_progress_; +inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { + return _impl_.stream_id_; } -inline void SetInProgressRequest::_internal_set_in_progress(bool value) { +inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { ; - _impl_.in_progress_ = value; + _impl_.stream_id_ = value; } // ------------------------------------------------------------------- -// SetInProgressResponse +// RespondStartVideoStreamingRequest + +// .mavsdk.rpc.camera_server.CameraFeedback start_video_streaming_feedback = 1; +inline void RespondStartVideoStreamingRequest::clear_start_video_streaming_feedback() { + _impl_.start_video_streaming_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::start_video_streaming_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) + return _internal_start_video_streaming_feedback(); +} +inline void RespondStartVideoStreamingRequest::set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_start_video_streaming_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStartVideoStreamingRequest.start_video_streaming_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStartVideoStreamingRequest::_internal_start_video_streaming_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.start_video_streaming_feedback_); +} +inline void RespondStartVideoStreamingRequest::_internal_set_start_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.start_video_streaming_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondStartVideoStreamingResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool SetInProgressResponse::has_camera_server_result() const { +inline bool RespondStartVideoStreamingResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void SetInProgressResponse::clear_camera_server_result() { +inline void RespondStartVideoStreamingResponse::clear_camera_server_result() { if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::_internal_camera_server_result() const { const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; return p != nullptr ? *p : reinterpret_cast( ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetInProgressResponse::camera_server_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStartVideoStreamingResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) return _internal_camera_server_result(); } -inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_result( +inline void RespondStartVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); @@ -6818,9 +9776,9 @@ inline void SetInProgressResponse::unsafe_arena_set_allocated_camera_server_resu } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::release_camera_server_result() { _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; @@ -6835,14 +9793,14 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse:: #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::unsafe_arena_release_camera_server_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::_internal_mutable_camera_server_result() { _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); @@ -6850,12 +9808,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse:: } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* SetInProgressResponse::mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStartVideoStreamingResponse::mutable_camera_server_result() { ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) return _msg; } -inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { +inline void RespondStartVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { delete _impl_.camera_server_result_; @@ -6872,147 +9830,150 @@ inline void SetInProgressResponse::set_allocated_camera_server_result(::mavsdk:: _impl_._has_bits_[0] &= ~0x00000001u; } _impl_.camera_server_result_ = camera_server_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetInProgressResponse.camera_server_result) -} - -// ------------------------------------------------------------------- - -// SubscribeTakePhotoRequest - -// ------------------------------------------------------------------- - -// TakePhotoResponse - -// int32 index = 1; -inline void TakePhotoResponse::clear_index() { - _impl_.index_ = 0; -} -inline ::int32_t TakePhotoResponse::index() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.TakePhotoResponse.index) - return _internal_index(); -} -inline void TakePhotoResponse::set_index(::int32_t value) { - _internal_set_index(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.TakePhotoResponse.index) -} -inline ::int32_t TakePhotoResponse::_internal_index() const { - return _impl_.index_; -} -inline void TakePhotoResponse::_internal_set_index(::int32_t value) { - ; - _impl_.index_ = value; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStartVideoStreamingResponse.camera_server_result) } // ------------------------------------------------------------------- -// SubscribeStartVideoRequest +// SubscribeStopVideoStreamingRequest // ------------------------------------------------------------------- -// StartVideoResponse +// StopVideoStreamingResponse // int32 stream_id = 1; -inline void StartVideoResponse::clear_stream_id() { +inline void StopVideoStreamingResponse::clear_stream_id() { _impl_.stream_id_ = 0; } -inline ::int32_t StartVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) +inline ::int32_t StopVideoStreamingResponse::stream_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) return _internal_stream_id(); } -inline void StartVideoResponse::set_stream_id(::int32_t value) { +inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoResponse.stream_id) + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) } -inline ::int32_t StartVideoResponse::_internal_stream_id() const { +inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { return _impl_.stream_id_; } -inline void StartVideoResponse::_internal_set_stream_id(::int32_t value) { +inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { ; _impl_.stream_id_ = value; } // ------------------------------------------------------------------- -// SubscribeStopVideoRequest - -// ------------------------------------------------------------------- - -// StopVideoResponse +// RespondStopVideoStreamingRequest -// int32 stream_id = 1; -inline void StopVideoResponse::clear_stream_id() { - _impl_.stream_id_ = 0; +// .mavsdk.rpc.camera_server.CameraFeedback stop_video_streaming_feedback = 1; +inline void RespondStopVideoStreamingRequest::clear_stop_video_streaming_feedback() { + _impl_.stop_video_streaming_feedback_ = 0; } -inline ::int32_t StopVideoResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) - return _internal_stream_id(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::stop_video_streaming_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) + return _internal_stop_video_streaming_feedback(); } -inline void StopVideoResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoResponse.stream_id) +inline void RespondStopVideoStreamingRequest::set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_stop_video_streaming_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStopVideoStreamingRequest.stop_video_streaming_feedback) } -inline ::int32_t StopVideoResponse::_internal_stream_id() const { - return _impl_.stream_id_; +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStopVideoStreamingRequest::_internal_stop_video_streaming_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.stop_video_streaming_feedback_); } -inline void StopVideoResponse::_internal_set_stream_id(::int32_t value) { +inline void RespondStopVideoStreamingRequest::_internal_set_stop_video_streaming_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { ; - _impl_.stream_id_ = value; + _impl_.stop_video_streaming_feedback_ = value; } // ------------------------------------------------------------------- -// SubscribeStartVideoStreamingRequest - -// ------------------------------------------------------------------- - -// StartVideoStreamingResponse +// RespondStopVideoStreamingResponse -// int32 stream_id = 1; -inline void StartVideoStreamingResponse::clear_stream_id() { - _impl_.stream_id_ = 0; +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondStopVideoStreamingResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; } -inline ::int32_t StartVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) - return _internal_stream_id(); +inline void RespondStopVideoStreamingResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; } -inline void StartVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StartVideoStreamingResponse.stream_id) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoStreamingResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline ::int32_t StartVideoStreamingResponse::_internal_stream_id() const { - return _impl_.stream_id_; +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondStopVideoStreamingResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void StartVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; +inline void RespondStopVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) } - -// ------------------------------------------------------------------- - -// SubscribeStopVideoStreamingRequest - -// ------------------------------------------------------------------- - -// StopVideoStreamingResponse - -// int32 stream_id = 1; -inline void StopVideoStreamingResponse::clear_stream_id() { - _impl_.stream_id_ = 0; +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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 ::int32_t StopVideoStreamingResponse::stream_id() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) - return _internal_stream_id(); +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; } -inline void StopVideoStreamingResponse::set_stream_id(::int32_t value) { - _internal_set_stream_id(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.StopVideoStreamingResponse.stream_id) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; } -inline ::int32_t StopVideoStreamingResponse::_internal_stream_id() const { - return _impl_.stream_id_; +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondStopVideoStreamingResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) + return _msg; } -inline void StopVideoStreamingResponse::_internal_set_stream_id(::int32_t value) { - ; - _impl_.stream_id_ = value; +inline void RespondStopVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondStopVideoStreamingResponse.camera_server_result) } // ------------------------------------------------------------------- @@ -7045,6 +10006,121 @@ inline void SetModeResponse::_internal_set_mode(::mavsdk::rpc::camera_server::Mo // ------------------------------------------------------------------- +// RespondSetModeRequest + +// .mavsdk.rpc.camera_server.CameraFeedback set_mode_feedback = 1; +inline void RespondSetModeRequest::clear_set_mode_feedback() { + _impl_.set_mode_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::set_mode_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) + return _internal_set_mode_feedback(); +} +inline void RespondSetModeRequest::set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_set_mode_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondSetModeRequest.set_mode_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondSetModeRequest::_internal_set_mode_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.set_mode_feedback_); +} +inline void RespondSetModeRequest::_internal_set_set_mode_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.set_mode_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondSetModeResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondSetModeResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void RespondSetModeResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondSetModeResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondSetModeResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void RespondSetModeResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* RespondSetModeResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondSetModeResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) + return _msg; +} +inline void RespondSetModeResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondSetModeResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + // SubscribeStorageInformationRequest // ------------------------------------------------------------------- @@ -7075,7 +10151,27 @@ inline void StorageInformationResponse::_internal_set_storage_id(::int32_t value // RespondStorageInformationRequest -// .mavsdk.rpc.camera_server.StorageInformation storage_information = 1; +// .mavsdk.rpc.camera_server.CameraFeedback storage_information_feedback = 1; +inline void RespondStorageInformationRequest::clear_storage_information_feedback() { + _impl_.storage_information_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::storage_information_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) + return _internal_storage_information_feedback(); +} +inline void RespondStorageInformationRequest::set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_storage_information_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondStorageInformationRequest.storage_information_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondStorageInformationRequest::_internal_storage_information_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.storage_information_feedback_); +} +inline void RespondStorageInformationRequest::_internal_set_storage_information_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.storage_information_feedback_ = value; +} + +// .mavsdk.rpc.camera_server.StorageInformation storage_information = 2; inline bool RespondStorageInformationRequest::has_storage_information() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.storage_information_ != nullptr); @@ -7285,7 +10381,27 @@ inline void CaptureStatusResponse::_internal_set_reserved(::int32_t value) { // RespondCaptureStatusRequest -// .mavsdk.rpc.camera_server.CaptureStatus capture_status = 1; +// .mavsdk.rpc.camera_server.CameraFeedback capture_status_feedback = 1; +inline void RespondCaptureStatusRequest::clear_capture_status_feedback() { + _impl_.capture_status_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::capture_status_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) + return _internal_capture_status_feedback(); +} +inline void RespondCaptureStatusRequest::set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_capture_status_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondCaptureStatusRequest.capture_status_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondCaptureStatusRequest::_internal_capture_status_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.capture_status_feedback_); +} +inline void RespondCaptureStatusRequest::_internal_set_capture_status_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.capture_status_feedback_ = value; +} + +// .mavsdk.rpc.camera_server.CaptureStatus capture_status = 2; inline bool RespondCaptureStatusRequest::has_capture_status() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.capture_status_ != nullptr); @@ -7493,92 +10609,68 @@ inline void FormatStorageResponse::_internal_set_storage_id(::int32_t value) { // ------------------------------------------------------------------- -// SubscribeResetSettingsRequest - -// ------------------------------------------------------------------- - -// ResetSettingsResponse +// RespondFormatStorageRequest -// int32 reserved = 1; -inline void ResetSettingsResponse::clear_reserved() { - _impl_.reserved_ = 0; +// .mavsdk.rpc.camera_server.CameraFeedback format_storage_feedback = 1; +inline void RespondFormatStorageRequest::clear_format_storage_feedback() { + _impl_.format_storage_feedback_ = 0; } -inline ::int32_t ResetSettingsResponse::reserved() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) - return _internal_reserved(); +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::format_storage_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) + return _internal_format_storage_feedback(); } -inline void ResetSettingsResponse::set_reserved(::int32_t value) { - _internal_set_reserved(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) +inline void RespondFormatStorageRequest::set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_format_storage_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondFormatStorageRequest.format_storage_feedback) } -inline ::int32_t ResetSettingsResponse::_internal_reserved() const { - return _impl_.reserved_; +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondFormatStorageRequest::_internal_format_storage_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.format_storage_feedback_); } -inline void ResetSettingsResponse::_internal_set_reserved(::int32_t value) { +inline void RespondFormatStorageRequest::_internal_set_format_storage_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { ; - _impl_.reserved_ = value; + _impl_.format_storage_feedback_ = value; } // ------------------------------------------------------------------- -// RespondTakePhotoRequest - -// .mavsdk.rpc.camera_server.TakePhotoFeedback take_photo_feedback = 1; -inline void RespondTakePhotoRequest::clear_take_photo_feedback() { - _impl_.take_photo_feedback_ = 0; -} -inline ::mavsdk::rpc::camera_server::TakePhotoFeedback RespondTakePhotoRequest::take_photo_feedback() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) - return _internal_take_photo_feedback(); -} -inline void RespondTakePhotoRequest::set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value) { - _internal_set_take_photo_feedback(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondTakePhotoRequest.take_photo_feedback) -} -inline ::mavsdk::rpc::camera_server::TakePhotoFeedback RespondTakePhotoRequest::_internal_take_photo_feedback() const { - return static_cast<::mavsdk::rpc::camera_server::TakePhotoFeedback>(_impl_.take_photo_feedback_); -} -inline void RespondTakePhotoRequest::_internal_set_take_photo_feedback(::mavsdk::rpc::camera_server::TakePhotoFeedback value) { - ; - _impl_.take_photo_feedback_ = value; -} +// RespondFormatStorageResponse -// .mavsdk.rpc.camera_server.CaptureInfo capture_info = 2; -inline bool RespondTakePhotoRequest::has_capture_info() const { +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool RespondFormatStorageResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.capture_info_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void RespondTakePhotoRequest::clear_capture_info() { - if (_impl_.capture_info_ != nullptr) _impl_.capture_info_->Clear(); +inline void RespondFormatStorageResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::_internal_capture_info() const { - const ::mavsdk::rpc::camera_server::CaptureInfo* p = _impl_.capture_info_; - return p != nullptr ? *p : reinterpret_cast( - ::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CaptureInfo& RespondTakePhotoRequest::capture_info() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) - return _internal_capture_info(); +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondFormatStorageResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) + return _internal_camera_server_result(); } -inline void RespondTakePhotoRequest::unsafe_arena_set_allocated_capture_info( - ::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { +inline void RespondFormatStorageResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { - delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.capture_info_); + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); } - _impl_.capture_info_ = capture_info; - if (capture_info) { + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::release_capture_info() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::release_camera_server_result() { _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; - _impl_.capture_info_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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); @@ -7590,70 +10682,122 @@ inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::relea #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::unsafe_arena_release_capture_info() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera_server::CaptureInfo* temp = _impl_.capture_info_; - _impl_.capture_info_ = nullptr; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::_internal_mutable_capture_info() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::_internal_mutable_camera_server_result() { _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.capture_info_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CaptureInfo>(GetArenaForAllocation()); - _impl_.capture_info_ = p; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; } - return _impl_.capture_info_; + return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CaptureInfo* RespondTakePhotoRequest::mutable_capture_info() { - ::mavsdk::rpc::camera_server::CaptureInfo* _msg = _internal_mutable_capture_info(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondFormatStorageResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) return _msg; } -inline void RespondTakePhotoRequest::set_allocated_capture_info(::mavsdk::rpc::camera_server::CaptureInfo* capture_info) { +inline void RespondFormatStorageResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { - delete _impl_.capture_info_; + delete _impl_.camera_server_result_; } - if (capture_info) { + if (camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = - ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(capture_info); + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); if (message_arena != submessage_arena) { - capture_info = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( - message_arena, capture_info, submessage_arena); + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); } _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.capture_info_ = capture_info; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoRequest.capture_info) + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondFormatStorageResponse.camera_server_result) } // ------------------------------------------------------------------- -// RespondTakePhotoResponse +// SubscribeResetSettingsRequest + +// ------------------------------------------------------------------- + +// ResetSettingsResponse + +// int32 reserved = 1; +inline void ResetSettingsResponse::clear_reserved() { + _impl_.reserved_ = 0; +} +inline ::int32_t ResetSettingsResponse::reserved() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) + return _internal_reserved(); +} +inline void ResetSettingsResponse::set_reserved(::int32_t value) { + _internal_set_reserved(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.ResetSettingsResponse.reserved) +} +inline ::int32_t ResetSettingsResponse::_internal_reserved() const { + return _impl_.reserved_; +} +inline void ResetSettingsResponse::_internal_set_reserved(::int32_t value) { + ; + _impl_.reserved_ = value; +} + +// ------------------------------------------------------------------- + +// RespondResetSettingsRequest + +// .mavsdk.rpc.camera_server.CameraFeedback reset_settings_feedback = 1; +inline void RespondResetSettingsRequest::clear_reset_settings_feedback() { + _impl_.reset_settings_feedback_ = 0; +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::reset_settings_feedback() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) + return _internal_reset_settings_feedback(); +} +inline void RespondResetSettingsRequest::set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + _internal_set_reset_settings_feedback(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.RespondResetSettingsRequest.reset_settings_feedback) +} +inline ::mavsdk::rpc::camera_server::CameraFeedback RespondResetSettingsRequest::_internal_reset_settings_feedback() const { + return static_cast<::mavsdk::rpc::camera_server::CameraFeedback>(_impl_.reset_settings_feedback_); +} +inline void RespondResetSettingsRequest::_internal_set_reset_settings_feedback(::mavsdk::rpc::camera_server::CameraFeedback value) { + ; + _impl_.reset_settings_feedback_ = value; +} + +// ------------------------------------------------------------------- + +// RespondResetSettingsResponse // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; -inline bool RespondTakePhotoResponse::has_camera_server_result() const { +inline bool RespondResetSettingsResponse::has_camera_server_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); return value; } -inline void RespondTakePhotoResponse::clear_camera_server_result() { +inline void RespondResetSettingsResponse::clear_camera_server_result() { if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::_internal_camera_server_result() const { +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::_internal_camera_server_result() const { const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; return p != nullptr ? *p : reinterpret_cast( ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); } -inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondTakePhotoResponse::camera_server_result() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) +inline const ::mavsdk::rpc::camera_server::CameraServerResult& RespondResetSettingsResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) return _internal_camera_server_result(); } -inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_result( +inline void RespondResetSettingsResponse::unsafe_arena_set_allocated_camera_server_result( ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { if (GetArenaForAllocation() == nullptr) { delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); @@ -7664,9 +10808,9 @@ inline void RespondTakePhotoResponse::unsafe_arena_set_allocated_camera_server_r } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::release_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::release_camera_server_result() { _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; @@ -7681,14 +10825,14 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoRespons #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::unsafe_arena_release_camera_server_result() { - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) _impl_._has_bits_[0] &= ~0x00000001u; ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; _impl_.camera_server_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::_internal_mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::_internal_mutable_camera_server_result() { _impl_._has_bits_[0] |= 0x00000001u; if (_impl_.camera_server_result_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); @@ -7696,12 +10840,12 @@ inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoRespons } return _impl_.camera_server_result_; } -inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondTakePhotoResponse::mutable_camera_server_result() { +inline ::mavsdk::rpc::camera_server::CameraServerResult* RespondResetSettingsResponse::mutable_camera_server_result() { ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) return _msg; } -inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { +inline void RespondResetSettingsResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); if (message_arena == nullptr) { delete _impl_.camera_server_result_; @@ -7718,7 +10862,7 @@ inline void RespondTakePhotoResponse::set_allocated_camera_server_result(::mavsd _impl_._has_bits_[0] &= ~0x00000001u; } _impl_.camera_server_result_ = camera_server_result; - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondTakePhotoResponse.camera_server_result) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.RespondResetSettingsResponse.camera_server_result) } // ------------------------------------------------------------------- @@ -8908,10 +12052,10 @@ inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::Cap return ::mavsdk::rpc::camera_server::CaptureStatus_VideoStatus_descriptor(); } template <> -struct is_proto_enum<::mavsdk::rpc::camera_server::TakePhotoFeedback> : std::true_type {}; +struct is_proto_enum<::mavsdk::rpc::camera_server::CameraFeedback> : std::true_type {}; template <> -inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::TakePhotoFeedback>() { - return ::mavsdk::rpc::camera_server::TakePhotoFeedback_descriptor(); +inline const EnumDescriptor* GetEnumDescriptor<::mavsdk::rpc::camera_server::CameraFeedback>() { + return ::mavsdk::rpc::camera_server::CameraFeedback_descriptor(); } template <> struct is_proto_enum<::mavsdk::rpc::camera_server::Mode> : std::true_type {}; diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index c5e2b0a010..22a56f9c64 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -44,41 +44,41 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer response->set_allocated_camera_server_result(rpc_camera_server_result); } - static rpc::camera_server::TakePhotoFeedback translateToRpcTakePhotoFeedback( - const mavsdk::CameraServer::TakePhotoFeedback& take_photo_feedback) + static rpc::camera_server::CameraFeedback + translateToRpcCameraFeedback(const mavsdk::CameraServer::CameraFeedback& camera_feedback) { - switch (take_photo_feedback) { + switch (camera_feedback) { default: - LogErr() << "Unknown take_photo_feedback enum value: " - << static_cast(take_photo_feedback); + LogErr() << "Unknown camera_feedback enum value: " + << static_cast(camera_feedback); // FALLTHROUGH - case mavsdk::CameraServer::TakePhotoFeedback::Unknown: - return rpc::camera_server::TAKE_PHOTO_FEEDBACK_UNKNOWN; - case mavsdk::CameraServer::TakePhotoFeedback::Ok: - return rpc::camera_server::TAKE_PHOTO_FEEDBACK_OK; - case mavsdk::CameraServer::TakePhotoFeedback::Busy: - return rpc::camera_server::TAKE_PHOTO_FEEDBACK_BUSY; - case mavsdk::CameraServer::TakePhotoFeedback::Failed: - return rpc::camera_server::TAKE_PHOTO_FEEDBACK_FAILED; + case mavsdk::CameraServer::CameraFeedback::Unknown: + return rpc::camera_server::CAMERA_FEEDBACK_UNKNOWN; + case mavsdk::CameraServer::CameraFeedback::Ok: + return rpc::camera_server::CAMERA_FEEDBACK_OK; + case mavsdk::CameraServer::CameraFeedback::Busy: + return rpc::camera_server::CAMERA_FEEDBACK_BUSY; + case mavsdk::CameraServer::CameraFeedback::Failed: + return rpc::camera_server::CAMERA_FEEDBACK_FAILED; } } - static mavsdk::CameraServer::TakePhotoFeedback translateFromRpcTakePhotoFeedback( - const rpc::camera_server::TakePhotoFeedback take_photo_feedback) + static mavsdk::CameraServer::CameraFeedback + translateFromRpcCameraFeedback(const rpc::camera_server::CameraFeedback camera_feedback) { - switch (take_photo_feedback) { + switch (camera_feedback) { default: - LogErr() << "Unknown take_photo_feedback enum value: " - << static_cast(take_photo_feedback); + LogErr() << "Unknown camera_feedback enum value: " + << static_cast(camera_feedback); // FALLTHROUGH - case rpc::camera_server::TAKE_PHOTO_FEEDBACK_UNKNOWN: - return mavsdk::CameraServer::TakePhotoFeedback::Unknown; - case rpc::camera_server::TAKE_PHOTO_FEEDBACK_OK: - return mavsdk::CameraServer::TakePhotoFeedback::Ok; - case rpc::camera_server::TAKE_PHOTO_FEEDBACK_BUSY: - return mavsdk::CameraServer::TakePhotoFeedback::Busy; - case rpc::camera_server::TAKE_PHOTO_FEEDBACK_FAILED: - return mavsdk::CameraServer::TakePhotoFeedback::Failed; + case rpc::camera_server::CAMERA_FEEDBACK_UNKNOWN: + return mavsdk::CameraServer::CameraFeedback::Unknown; + case rpc::camera_server::CAMERA_FEEDBACK_OK: + return mavsdk::CameraServer::CameraFeedback::Ok; + case rpc::camera_server::CAMERA_FEEDBACK_BUSY: + return mavsdk::CameraServer::CameraFeedback::Busy; + case rpc::camera_server::CAMERA_FEEDBACK_FAILED: + return mavsdk::CameraServer::CameraFeedback::Failed; } } @@ -699,7 +699,7 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } auto result = _lazy_plugin.maybe_plugin()->respond_take_photo( - translateFromRpcTakePhotoFeedback(request->take_photo_feedback()), + translateFromRpcCameraFeedback(request->take_photo_feedback()), translateFromRpcCaptureInfo(request->capture_info())); if (response != nullptr) { @@ -750,6 +750,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondStartVideo( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondStartVideoRequest* request, + rpc::camera_server::RespondStartVideoResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondStartVideo sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_start_video( + translateFromRpcCameraFeedback(request->start_video_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeStopVideo( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeStopVideoRequest* /* request */, @@ -791,6 +822,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondStopVideo( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondStopVideoRequest* request, + rpc::camera_server::RespondStopVideoResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondStopVideo sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_stop_video( + translateFromRpcCameraFeedback(request->stop_video_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeStartVideoStreaming( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* /* request */, @@ -832,6 +894,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondStartVideoStreaming( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondStartVideoStreamingRequest* request, + rpc::camera_server::RespondStartVideoStreamingResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondStartVideoStreaming sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_start_video_streaming( + translateFromRpcCameraFeedback(request->start_video_streaming_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeStopVideoStreaming( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* /* request */, @@ -873,6 +966,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondStopVideoStreaming( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondStopVideoStreamingRequest* request, + rpc::camera_server::RespondStopVideoStreamingResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondStopVideoStreaming sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_stop_video_streaming( + translateFromRpcCameraFeedback(request->stop_video_streaming_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeSetMode( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeSetModeRequest* /* request */, @@ -914,6 +1038,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondSetMode( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondSetModeRequest* request, + rpc::camera_server::RespondSetModeResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondSetMode sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_set_mode( + translateFromRpcCameraFeedback(request->set_mode_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeStorageInformation( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* /* request */, @@ -977,6 +1132,7 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } auto result = _lazy_plugin.maybe_plugin()->respond_storage_information( + translateFromRpcCameraFeedback(request->storage_information_feedback()), translateFromRpcStorageInformation(request->storage_information())); if (response != nullptr) { @@ -1049,6 +1205,7 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer } auto result = _lazy_plugin.maybe_plugin()->respond_capture_status( + translateFromRpcCameraFeedback(request->capture_status_feedback()), translateFromRpcCaptureStatus(request->capture_status())); if (response != nullptr) { @@ -1099,6 +1256,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondFormatStorage( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondFormatStorageRequest* request, + rpc::camera_server::RespondFormatStorageResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondFormatStorage sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_format_storage( + translateFromRpcCameraFeedback(request->format_storage_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeResetSettings( grpc::ServerContext* /* context */, const mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* /* request */, @@ -1140,6 +1328,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status RespondResetSettings( + grpc::ServerContext* /* context */, + const rpc::camera_server::RespondResetSettingsRequest* request, + rpc::camera_server::RespondResetSettingsResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "RespondResetSettings sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->respond_reset_settings( + translateFromRpcCameraFeedback(request->reset_settings_feedback())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); diff --git a/src/system_tests/camera_take_photo.cpp b/src/system_tests/camera_take_photo.cpp index 20eecde254..6347df3ba5 100644 --- a/src/system_tests/camera_take_photo.cpp +++ b/src/system_tests/camera_take_photo.cpp @@ -26,7 +26,7 @@ TEST(SystemTest, CameraTakePhoto) info.index = index; info.is_success = true; - camera_server.respond_take_photo(CameraServer::TakePhotoFeedback::Ok, info); + camera_server.respond_take_photo(CameraServer::CameraFeedback::Ok, info); }); auto prom = std::promise>(); From 207bffce64a4d6681d23a9acbc0ad34e9ffc9be1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 1 Nov 2023 17:57:43 +1300 Subject: [PATCH 09/25] proto: small updates Signed-off-by: Julian Oes --- proto | 2 +- .../include/plugins/camera_server/camera_server.h | 5 +++-- .../generated/camera_server/camera_server.grpc.pb.h | 12 ++++++------ 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/proto b/proto index 53cecadc43..8184c04888 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 53cecadc43146ff44545302b3742f74534f0efd1 +Subproject commit 8184c0488859bdfcdda4aa88efa46acccd9c204c diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index ef33caef52..6f84fe7cc5 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -421,7 +421,7 @@ class CameraServer : public ServerPluginBase { using StartVideoHandle = Handle; /** - * @brief Subscribe to start video requests. Each request received should response to using + * @brief Subscribe to start video requests. Each request received should respond to using * RespondStartVideo */ StartVideoHandle subscribe_start_video(const StartVideoCallback& callback); @@ -432,7 +432,8 @@ class CameraServer : public ServerPluginBase { void unsubscribe_start_video(StartVideoHandle handle); /** - * @brief Respond to start video request from SubscribeStartVideo. + * @brief Subscribe to stop video requests. Each request received should respond using + * StopVideoResponse * * This function is blocking. * diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index d547c610e6..22b1757edf 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -72,7 +72,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> PrepareAsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(PrepareAsyncRespondTakePhotoRaw(context, request, cq)); } - // Subscribe to start video requests. Each request received should response to using RespondStartVideo + // Subscribe to start video requests. Each request received should respond to using RespondStartVideo std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(SubscribeStartVideoRaw(context, request)); } @@ -82,7 +82,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>> PrepareAsyncSubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::StartVideoResponse>>(PrepareAsyncSubscribeStartVideoRaw(context, request, cq)); } - // Respond to start video request from SubscribeStartVideo. + // Subscribe to stop video requests. Each request received should respond using StopVideoResponse virtual ::grpc::Status RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>> AsyncRespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>>(AsyncRespondStartVideoRaw(context, request, cq)); @@ -248,9 +248,9 @@ class CameraServerService final { // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to start video requests. Each request received should response to using RespondStartVideo + // Subscribe to start video requests. Each request received should respond to using RespondStartVideo virtual void SubscribeStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::StartVideoResponse>* reactor) = 0; - // Respond to start video request from SubscribeStartVideo. + // Subscribe to stop video requests. Each request received should respond using StopVideoResponse virtual void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, std::function) = 0; virtual void RespondStartVideo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Subscribe to stop video requests. Each request received should response to using RespondStopVideo @@ -669,9 +669,9 @@ class CameraServerService final { virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); - // Subscribe to start video requests. Each request received should response to using RespondStartVideo + // Subscribe to start video requests. Each request received should respond to using RespondStartVideo virtual ::grpc::Status SubscribeStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer); - // Respond to start video request from SubscribeStartVideo. + // Subscribe to stop video requests. Each request received should respond using StopVideoResponse virtual ::grpc::Status RespondStartVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response); // Subscribe to stop video requests. Each request received should response to using RespondStopVideo virtual ::grpc::Status SubscribeStopVideo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer); From a11edb406c9372c1bce9550147f1915e2f7c9da1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 2 Nov 2023 21:36:03 +1300 Subject: [PATCH 10/25] camera_server: add video stream info This required the MAVLink headers to be updated. Signed-off-by: Julian Oes --- .../plugins/camera_server/camera_server.cpp | 21 + .../camera_server/camera_server_impl.cpp | 93 +- .../camera_server/camera_server_impl.h | 3 + .../plugins/camera_server/camera_server.h | 33 + .../manual_control/manual_control_impl.cpp | 8 +- .../camera_server/camera_server.grpc.pb.cc | 124 +- .../camera_server/camera_server.grpc.pb.h | 526 ++++--- .../camera_server/camera_server.pb.cc | 1208 +++++++++++++---- .../camera_server/camera_server.pb.h | 977 +++++++++++-- .../camera_server_service_impl.h | 55 + third_party/mavlink/CMakeLists.txt | 2 +- 11 files changed, 2481 insertions(+), 569 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index 5d343cffcc..ef75fa7cc0 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -11,6 +11,7 @@ namespace mavsdk { using Information = CameraServer::Information; +using VideoStreaming = CameraServer::VideoStreaming; using Position = CameraServer::Position; using Quaternion = CameraServer::Quaternion; using CaptureInfo = CameraServer::CaptureInfo; @@ -30,6 +31,11 @@ CameraServer::Result CameraServer::set_information(Information information) cons return _impl->set_information(information); } +CameraServer::Result CameraServer::set_video_streaming(VideoStreaming video_streaming) const +{ + return _impl->set_video_streaming(video_streaming); +} + CameraServer::Result CameraServer::set_in_progress(bool in_progress) const { return _impl->set_in_progress(in_progress); @@ -236,6 +242,21 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf return str; } +bool operator==(const CameraServer::VideoStreaming& lhs, const CameraServer::VideoStreaming& rhs) +{ + return (rhs.has_rtsp_server == lhs.has_rtsp_server) && (rhs.rtsp_uri == lhs.rtsp_uri); +} + +std::ostream& operator<<(std::ostream& str, CameraServer::VideoStreaming const& video_streaming) +{ + str << std::setprecision(15); + str << "video_streaming:" << '\n' << "{\n"; + str << " has_rtsp_server: " << video_streaming.has_rtsp_server << '\n'; + str << " rtsp_uri: " << video_streaming.rtsp_uri << '\n'; + str << '}'; + return str; +} + bool operator==(const CameraServer::Position& lhs, const CameraServer::Position& rhs) { return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 90a3ebf555..2a9bcc1546 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -188,6 +188,17 @@ CameraServer::Result CameraServerImpl::set_information(CameraServer::Information return CameraServer::Result::Success; } +CameraServer::Result +CameraServerImpl::set_video_streaming(CameraServer::VideoStreaming video_streaming) +{ + // TODO: validate uri length + + _is_video_streaming_set = true; + _video_streaming = video_streaming; + + return CameraServer::Result::Success; +} + CameraServer::Result CameraServerImpl::set_in_progress(bool in_progress) { _is_image_capture_in_progress = in_progress; @@ -835,6 +846,7 @@ void CameraServerImpl::stop_image_capture_interval() std::optional CameraServerImpl::process_camera_information_request( const MavlinkCommandReceiver::CommandLong& command) { + LogWarn() << "Camera info request"; auto capabilities = static_cast(command.params.param1); if (!capabilities) { @@ -869,6 +881,15 @@ std::optional CameraServerImpl::process_camera_informatio capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; } + if (_is_video_streaming_set) { + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; + } + + _information.vendor_name.resize(sizeof(mavlink_camera_information_t::vendor_name)); + _information.model_name.resize(sizeof(mavlink_camera_information_t::model_name)); + _information.definition_file_uri.resize( + sizeof(mavlink_camera_information_t::cam_definition_uri)); + _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message{}; mavlink_msg_camera_information_pack_chan( @@ -888,7 +909,8 @@ std::optional CameraServerImpl::process_camera_informatio _information.lens_id, capability_flags, _information.definition_file_version, - _information.definition_file_uri.c_str()); + _information.definition_file_uri.c_str(), + 0); return message; }); LogDebug() << "sent info msg"; @@ -1342,10 +1364,43 @@ std::optional CameraServerImpl::process_video_stream_info UNUSED(stream_id); - LogDebug() << "unsupported video stream information request"; + if (_is_video_streaming_set) { + auto command_ack = _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + LogDebug() << "sent video streaming ack"; + + const char name[32] = ""; + + _video_streaming.rtsp_uri.resize(sizeof(mavlink_video_stream_information_t::uri)); + + mavlink_message_t msg{}; + mavlink_msg_video_stream_information_pack( + _server_component_impl->get_own_system_id(), + _server_component_impl->get_own_component_id(), + &msg, + 0, // Stream id + 0, // Count + VIDEO_STREAM_TYPE_RTSP, + VIDEO_STREAM_STATUS_FLAGS_RUNNING, + 0, // famerate + 0, // resolution horizontal + 0, // resolution vertical + 0, // bitrate + 0, // rotation + 0, // horizontal field of view + name, + _video_streaming.rtsp_uri.c_str()); + + _server_component_impl->send_message(msg); + + // Ack already sent. + return std::nullopt; - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } else { + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } } std::optional CameraServerImpl::process_video_stream_status_request( @@ -1355,10 +1410,34 @@ std::optional CameraServerImpl::process_video_stream_stat UNUSED(stream_id); - LogDebug() << "unsupported video stream status request"; + if (!_is_video_streaming_set) { + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + } - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_UNSUPPORTED); + auto command_ack = + _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); + _server_component_impl->send_command_ack(command_ack); + LogDebug() << "sent video streaming ack"; + + mavlink_message_t msg{}; + mavlink_msg_video_stream_status_pack( + _server_component_impl->get_own_system_id(), + _server_component_impl->get_own_component_id(), + &msg, + 0, // Stream id + VIDEO_STREAM_STATUS_FLAGS_RUNNING, + 0, // framerate + 0, // resolution horizontal + 0, // resolution vertical + 0, // bitrate + 0, // rotation + 0 // horizontal field of view + ); + _server_component_impl->send_message(msg); + + // ack was already sent + return std::nullopt; } } // namespace mavsdk diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 474a3e4b01..a88f728790 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -15,6 +15,7 @@ class CameraServerImpl : public ServerPluginImplBase { void deinit() override; CameraServer::Result set_information(CameraServer::Information information); + CameraServer::Result set_video_streaming(CameraServer::VideoStreaming video_streaming); CameraServer::Result set_in_progress(bool in_progress); CameraServer::TakePhotoHandle @@ -89,6 +90,8 @@ class CameraServerImpl : public ServerPluginImplBase { bool _is_information_set{}; CameraServer::Information _information{}; + bool _is_video_streaming_set{}; + CameraServer::VideoStreaming _video_streaming{}; // CAMERA_CAPTURE_STATUS fields // TODO: how do we keep this info in sync between plugin instances? diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 6f84fe7cc5..e92f0661e1 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -115,6 +115,30 @@ class CameraServer : public ServerPluginBase { friend std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information); + /** + * @brief Type to represent video streaming settings + */ + struct VideoStreaming { + bool has_rtsp_server{}; /**< @brief True if the capture was successful */ + std::string rtsp_uri{}; /**< @brief RTSP URI (e.g. rtsp://192.168.1.42:8554/live) */ + }; + + /** + * @brief Equal operator to compare two `CameraServer::VideoStreaming` objects. + * + * @return `true` if items are equal. + */ + friend bool + operator==(const CameraServer::VideoStreaming& lhs, const CameraServer::VideoStreaming& rhs); + + /** + * @brief Stream operator to print information about a `CameraServer::VideoStreaming`. + * + * @return A reference to the stream. + */ + friend std::ostream& + operator<<(std::ostream& str, CameraServer::VideoStreaming const& video_streaming); + /** * @brief Position type in global coordinates. */ @@ -370,6 +394,15 @@ class CameraServer : public ServerPluginBase { */ Result set_information(Information information) const; + /** + * @brief Sets video streaming settings. + * + * This function is blocking. + * + * @return Result of request. + */ + Result set_video_streaming(VideoStreaming video_streaming) const; + /** * @brief Sets image capture in progress status flags. This should be set to true when the * camera is busy taking a photo and false when it is done. diff --git a/src/mavsdk/plugins/manual_control/manual_control_impl.cpp b/src/mavsdk/plugins/manual_control/manual_control_impl.cpp index 57f217fa30..b5c36f2326 100644 --- a/src/mavsdk/plugins/manual_control/manual_control_impl.cpp +++ b/src/mavsdk/plugins/manual_control/manual_control_impl.cpp @@ -122,7 +122,13 @@ ManualControlImpl::set_manual_control_input(float x, float y, float z, float r) buttons2, enabled_extensions, pitch_only_axis, - roll_only_axis); + roll_only_axis, + 0, + 0, + 0, + 0, + 0, + 0); return message; }) ? ManualControl::Result::Success : diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc index adc2c9615e..ecbb047d4b 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.cc @@ -25,6 +25,7 @@ namespace camera_server { static const char* CameraServerService_method_names[] = { "/mavsdk.rpc.camera_server.CameraServerService/SetInformation", + "/mavsdk.rpc.camera_server.CameraServerService/SetVideoStreaming", "/mavsdk.rpc.camera_server.CameraServerService/SetInProgress", "/mavsdk.rpc.camera_server.CameraServerService/SubscribeTakePhoto", "/mavsdk.rpc.camera_server.CameraServerService/RespondTakePhoto", @@ -56,27 +57,28 @@ std::unique_ptr< CameraServerService::Stub> CameraServerService::NewStub(const s CameraServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) : channel_(channel), rpcmethod_SetInformation_(CameraServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetInProgress_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStartVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStopVideo_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStartVideoStreaming_(CameraServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStopVideoStreaming_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondSetMode_(CameraServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeStorageInformation_(CameraServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeFormatStorage_(CameraServerService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondFormatStorage_(CameraServerService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_RespondResetSettings_(CameraServerService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetVideoStreaming_(CameraServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetInProgress_(CameraServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeTakePhoto_(CameraServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondTakePhoto_(CameraServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStartVideo_(CameraServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStartVideo_(CameraServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStopVideo_(CameraServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStopVideo_(CameraServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStartVideoStreaming_(CameraServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStartVideoStreaming_(CameraServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStopVideoStreaming_(CameraServerService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStopVideoStreaming_(CameraServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeSetMode_(CameraServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondSetMode_(CameraServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeStorageInformation_(CameraServerService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondStorageInformation_(CameraServerService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCaptureStatus_(CameraServerService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondCaptureStatus_(CameraServerService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeFormatStorage_(CameraServerService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondFormatStorage_(CameraServerService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeResetSettings_(CameraServerService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_RespondResetSettings_(CameraServerService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status CameraServerService::Stub::SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) { @@ -102,6 +104,29 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationR return result; } +::grpc::Status CameraServerService::Stub::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetVideoStreaming_, context, request, response); +} + +void CameraServerService::Stub::async::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreaming_, context, request, response, std::move(f)); +} + +void CameraServerService::Stub::async::SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetVideoStreaming_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* CameraServerService::Stub::PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetVideoStreaming_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* CameraServerService::Stub::AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetVideoStreamingRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::Status CameraServerService::Stub::SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetInProgress_, context, request, response); } @@ -529,6 +554,16 @@ CameraServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraServerService_method_names[1], ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* req, + ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* resp) { + return service->SetVideoStreaming(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraServerService_method_names[2], + ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, ::grpc::ServerContext* ctx, @@ -537,7 +572,7 @@ CameraServerService::Service::Service() { return service->SetInProgress(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[2], + CameraServerService_method_names[3], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( [](CameraServerService::Service* service, @@ -547,7 +582,7 @@ CameraServerService::Service::Service() { return service->SubscribeTakePhoto(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[3], + CameraServerService_method_names[4], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -557,7 +592,7 @@ CameraServerService::Service::Service() { return service->RespondTakePhoto(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[4], + CameraServerService_method_names[5], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( [](CameraServerService::Service* service, @@ -567,7 +602,7 @@ CameraServerService::Service::Service() { return service->SubscribeStartVideo(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[5], + CameraServerService_method_names[6], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -577,7 +612,7 @@ CameraServerService::Service::Service() { return service->RespondStartVideo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[6], + CameraServerService_method_names[7], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [](CameraServerService::Service* service, @@ -587,7 +622,7 @@ CameraServerService::Service::Service() { return service->SubscribeStopVideo(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[7], + CameraServerService_method_names[8], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -597,7 +632,7 @@ CameraServerService::Service::Service() { return service->RespondStopVideo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[8], + CameraServerService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [](CameraServerService::Service* service, @@ -607,7 +642,7 @@ CameraServerService::Service::Service() { return service->SubscribeStartVideoStreaming(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[9], + CameraServerService_method_names[10], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -617,7 +652,7 @@ CameraServerService::Service::Service() { return service->RespondStartVideoStreaming(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[10], + CameraServerService_method_names[11], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [](CameraServerService::Service* service, @@ -627,7 +662,7 @@ CameraServerService::Service::Service() { return service->SubscribeStopVideoStreaming(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[11], + CameraServerService_method_names[12], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -637,7 +672,7 @@ CameraServerService::Service::Service() { return service->RespondStopVideoStreaming(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[12], + CameraServerService_method_names[13], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [](CameraServerService::Service* service, @@ -647,7 +682,7 @@ CameraServerService::Service::Service() { return service->SubscribeSetMode(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[13], + CameraServerService_method_names[14], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -657,7 +692,7 @@ CameraServerService::Service::Service() { return service->RespondSetMode(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[14], + CameraServerService_method_names[15], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [](CameraServerService::Service* service, @@ -667,7 +702,7 @@ CameraServerService::Service::Service() { return service->SubscribeStorageInformation(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[15], + CameraServerService_method_names[16], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -677,7 +712,7 @@ CameraServerService::Service::Service() { return service->RespondStorageInformation(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[16], + CameraServerService_method_names[17], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [](CameraServerService::Service* service, @@ -687,7 +722,7 @@ CameraServerService::Service::Service() { return service->SubscribeCaptureStatus(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[17], + CameraServerService_method_names[18], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -697,7 +732,7 @@ CameraServerService::Service::Service() { return service->RespondCaptureStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[18], + CameraServerService_method_names[19], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [](CameraServerService::Service* service, @@ -707,7 +742,7 @@ CameraServerService::Service::Service() { return service->SubscribeFormatStorage(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[19], + CameraServerService_method_names[20], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -717,7 +752,7 @@ CameraServerService::Service::Service() { return service->RespondFormatStorage(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[20], + CameraServerService_method_names[21], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [](CameraServerService::Service* service, @@ -727,7 +762,7 @@ CameraServerService::Service::Service() { return service->SubscribeResetSettings(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraServerService_method_names[21], + CameraServerService_method_names[22], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraServerService::Service, ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraServerService::Service* service, @@ -748,6 +783,13 @@ ::grpc::Status CameraServerService::Service::SetInformation(::grpc::ServerContex return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraServerService::Service::SetVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraServerService::Service::SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { (void) context; (void) request; diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index 22b1757edf..df7b4635f3 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -46,6 +46,14 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } + // Sets video streaming settings. + virtual ::grpc::Status SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> AsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(AsyncSetVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> PrepareAsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(PrepareAsyncSetVideoStreamingRaw(context, request, cq)); + } // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { @@ -240,6 +248,9 @@ class CameraServerService final { // Sets the camera information. This must be called as soon as the camera server is created. virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) = 0; virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Sets video streaming settings. + virtual void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function) = 0; + virtual void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) = 0; virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -300,6 +311,8 @@ class CameraServerService final { private: virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) = 0; @@ -363,6 +376,13 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } + ::grpc::Status SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> AsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(AsyncSetVideoStreamingRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>> PrepareAsyncSetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>>(PrepareAsyncSetVideoStreamingRaw(context, request, cq)); + } ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(AsyncSetInProgressRaw(context, request, cq)); @@ -535,6 +555,8 @@ class CameraServerService final { public: void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) override; void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, std::function) override; + void SetVideoStreaming(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) override; void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) override; @@ -580,6 +602,8 @@ class CameraServerService final { class async async_stub_{this}; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* AsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInformationResponse>* PrepareAsyncSetInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* AsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* PrepareAsyncSetVideoStreamingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* AsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::SetInProgressResponse>* PrepareAsyncSetInProgressRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera_server::TakePhotoResponse>* SubscribeTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) override; @@ -633,6 +657,7 @@ class CameraServerService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* AsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* PrepareAsyncRespondResetSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetInformation_; + const ::grpc::internal::RpcMethod rpcmethod_SetVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SetInProgress_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeTakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_RespondTakePhoto_; @@ -663,6 +688,8 @@ class CameraServerService final { virtual ~Service(); // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response); + // Sets video streaming settings. + virtual ::grpc::Status SetVideoStreaming(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response); // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. @@ -727,12 +754,32 @@ class CameraServerService final { } }; template + class WithAsyncMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodAsync(1); + } + ~WithAsyncMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetInProgress() { - ::grpc::Service::MarkMethodAsync(1); + ::grpc::Service::MarkMethodAsync(2); } ~WithAsyncMethod_SetInProgress() override { BaseClassMustBeDerivedFromService(this); @@ -743,7 +790,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetInProgress(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::SetInProgressResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -752,7 +799,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodAsync(2); + ::grpc::Service::MarkMethodAsync(3); } ~WithAsyncMethod_SubscribeTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -763,7 +810,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeTakePhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(3, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -772,7 +819,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodAsync(3); + ::grpc::Service::MarkMethodAsync(4); } ~WithAsyncMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -783,7 +830,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondTakePhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -792,7 +839,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodAsync(4); + ::grpc::Service::MarkMethodAsync(5); } ~WithAsyncMethod_SubscribeStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -803,7 +850,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(4, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -812,7 +859,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodAsync(5); + ::grpc::Service::MarkMethodAsync(6); } ~WithAsyncMethod_RespondStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -823,7 +870,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -832,7 +879,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(7); } ~WithAsyncMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -843,7 +890,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -852,7 +899,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_RespondStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -863,7 +910,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -872,7 +919,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(9); } ~WithAsyncMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -883,7 +930,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -892,7 +939,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodAsync(9); + ::grpc::Service::MarkMethodAsync(10); } ~WithAsyncMethod_RespondStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -903,7 +950,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -912,7 +959,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodAsync(10); + ::grpc::Service::MarkMethodAsync(11); } ~WithAsyncMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -923,7 +970,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -932,7 +979,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodAsync(11); + ::grpc::Service::MarkMethodAsync(12); } ~WithAsyncMethod_RespondStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -943,7 +990,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(12, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -952,7 +999,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodAsync(12); + ::grpc::Service::MarkMethodAsync(13); } ~WithAsyncMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -963,7 +1010,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::SetModeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -972,7 +1019,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondSetMode() { - ::grpc::Service::MarkMethodAsync(13); + ::grpc::Service::MarkMethodAsync(14); } ~WithAsyncMethod_RespondSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -983,7 +1030,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondSetModeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(13, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(14, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -992,7 +1039,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodAsync(14); + ::grpc::Service::MarkMethodAsync(15); } ~WithAsyncMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1003,7 +1050,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::StorageInformationResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1012,7 +1059,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodAsync(15); + ::grpc::Service::MarkMethodAsync(16); } ~WithAsyncMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1023,7 +1070,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStorageInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(15, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(16, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1032,7 +1079,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodAsync(16); + ::grpc::Service::MarkMethodAsync(17); } ~WithAsyncMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1043,7 +1090,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::CaptureStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1052,7 +1099,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodAsync(17); + ::grpc::Service::MarkMethodAsync(18); } ~WithAsyncMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1063,7 +1110,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondCaptureStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(17, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(18, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1072,7 +1119,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodAsync(18); + ::grpc::Service::MarkMethodAsync(19); } ~WithAsyncMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -1083,7 +1130,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::FormatStorageResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1092,7 +1139,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodAsync(19); + ::grpc::Service::MarkMethodAsync(20); } ~WithAsyncMethod_RespondFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -1103,7 +1150,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(19, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1112,7 +1159,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodAsync(20); + ::grpc::Service::MarkMethodAsync(21); } ~WithAsyncMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1123,7 +1170,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera_server::ResetSettingsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(21, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1132,7 +1179,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodAsync(21); + ::grpc::Service::MarkMethodAsync(22); } ~WithAsyncMethod_RespondResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1143,10 +1190,10 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondResetSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > AsyncService; + typedef WithAsyncMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SetInformation : public BaseClass { private: @@ -1175,18 +1222,45 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetInformationRequest* /*request*/, ::mavsdk::rpc::camera_server::SetInformationResponse* /*response*/) { return nullptr; } }; template + class WithCallbackMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* response) { return this->SetVideoStreaming(context, request, response); }));} + void SetMessageAllocatorFor_SetVideoStreaming( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetInProgress() { - ::grpc::Service::MarkMethodCallback(1, + ::grpc::Service::MarkMethodCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) { return this->SetInProgress(context, request, response); }));} void SetMessageAllocatorFor_SetInProgress( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1207,7 +1281,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodCallback(2, + ::grpc::Service::MarkMethodCallback(3, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request) { return this->SubscribeTakePhoto(context, request); })); @@ -1229,13 +1303,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodCallback(3, + ::grpc::Service::MarkMethodCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) { return this->RespondTakePhoto(context, request, response); }));} void SetMessageAllocatorFor_RespondTakePhoto( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1256,7 +1330,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodCallback(4, + ::grpc::Service::MarkMethodCallback(5, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest* request) { return this->SubscribeStartVideo(context, request); })); @@ -1278,13 +1352,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodCallback(5, + ::grpc::Service::MarkMethodCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoResponse* response) { return this->RespondStartVideo(context, request, response); }));} void SetMessageAllocatorFor_RespondStartVideo( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1305,7 +1379,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(7, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest* request) { return this->SubscribeStopVideo(context, request); })); @@ -1327,13 +1401,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodCallback(7, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoResponse* response) { return this->RespondStopVideo(context, request, response); }));} void SetMessageAllocatorFor_RespondStopVideo( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(8); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1354,7 +1428,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodCallback(8, + ::grpc::Service::MarkMethodCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest* request) { return this->SubscribeStartVideoStreaming(context, request); })); @@ -1376,13 +1450,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodCallback(9, + ::grpc::Service::MarkMethodCallback(10, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse* response) { return this->RespondStartVideoStreaming(context, request, response); }));} void SetMessageAllocatorFor_RespondStartVideoStreaming( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(9); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(10); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1403,7 +1477,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodCallback(10, + ::grpc::Service::MarkMethodCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest* request) { return this->SubscribeStopVideoStreaming(context, request); })); @@ -1425,13 +1499,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodCallback(11, + ::grpc::Service::MarkMethodCallback(12, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest* request, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse* response) { return this->RespondStopVideoStreaming(context, request, response); }));} void SetMessageAllocatorFor_RespondStopVideoStreaming( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(11); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(12); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1452,7 +1526,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodCallback(12, + ::grpc::Service::MarkMethodCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeSetModeRequest* request) { return this->SubscribeSetMode(context, request); })); @@ -1474,13 +1548,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondSetMode() { - ::grpc::Service::MarkMethodCallback(13, + ::grpc::Service::MarkMethodCallback(14, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondSetModeRequest* request, ::mavsdk::rpc::camera_server::RespondSetModeResponse* response) { return this->RespondSetMode(context, request, response); }));} void SetMessageAllocatorFor_RespondSetMode( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(13); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(14); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1501,7 +1575,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodCallback(14, + ::grpc::Service::MarkMethodCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest* request) { return this->SubscribeStorageInformation(context, request); })); @@ -1523,13 +1597,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodCallback(15, + ::grpc::Service::MarkMethodCallback(16, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondStorageInformationRequest* request, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse* response) { return this->RespondStorageInformation(context, request, response); }));} void SetMessageAllocatorFor_RespondStorageInformation( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(15); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(16); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1550,7 +1624,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodCallback(16, + ::grpc::Service::MarkMethodCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest* request) { return this->SubscribeCaptureStatus(context, request); })); @@ -1572,13 +1646,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodCallback(17, + ::grpc::Service::MarkMethodCallback(18, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest* request, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse* response) { return this->RespondCaptureStatus(context, request, response); }));} void SetMessageAllocatorFor_RespondCaptureStatus( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(17); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(18); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1599,7 +1673,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodCallback(18, + ::grpc::Service::MarkMethodCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest* request) { return this->SubscribeFormatStorage(context, request); })); @@ -1621,13 +1695,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodCallback(19, + ::grpc::Service::MarkMethodCallback(20, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondFormatStorageRequest* request, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse* response) { return this->RespondFormatStorage(context, request, response); }));} void SetMessageAllocatorFor_RespondFormatStorage( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(19); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(20); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1648,7 +1722,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodCallback(20, + ::grpc::Service::MarkMethodCallback(21, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest* request) { return this->SubscribeResetSettings(context, request); })); @@ -1670,13 +1744,13 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodCallback(21, + ::grpc::Service::MarkMethodCallback(22, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* request, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* response) { return this->RespondResetSettings(context, request, response); }));} void SetMessageAllocatorFor_RespondResetSettings( ::grpc::MessageAllocator< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(21); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(22); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1691,7 +1765,7 @@ class CameraServerService final { virtual ::grpc::ServerUnaryReactor* RespondResetSettings( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera_server::RespondResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > CallbackService; + typedef WithCallbackMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetInformation : public BaseClass { @@ -1711,12 +1785,29 @@ class CameraServerService final { } }; template + class WithGenericMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodGeneric(1); + } + ~WithGenericMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetInProgress() { - ::grpc::Service::MarkMethodGeneric(1); + ::grpc::Service::MarkMethodGeneric(2); } ~WithGenericMethod_SetInProgress() override { BaseClassMustBeDerivedFromService(this); @@ -1733,7 +1824,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodGeneric(2); + ::grpc::Service::MarkMethodGeneric(3); } ~WithGenericMethod_SubscribeTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -1750,7 +1841,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodGeneric(3); + ::grpc::Service::MarkMethodGeneric(4); } ~WithGenericMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -1767,7 +1858,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodGeneric(4); + ::grpc::Service::MarkMethodGeneric(5); } ~WithGenericMethod_SubscribeStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1784,7 +1875,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodGeneric(5); + ::grpc::Service::MarkMethodGeneric(6); } ~WithGenericMethod_RespondStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1801,7 +1892,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(7); } ~WithGenericMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1818,7 +1909,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_RespondStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1835,7 +1926,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(9); } ~WithGenericMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1852,7 +1943,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(9); + ::grpc::Service::MarkMethodGeneric(10); } ~WithGenericMethod_RespondStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1869,7 +1960,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(10); + ::grpc::Service::MarkMethodGeneric(11); } ~WithGenericMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1886,7 +1977,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(11); + ::grpc::Service::MarkMethodGeneric(12); } ~WithGenericMethod_RespondStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1903,7 +1994,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodGeneric(12); + ::grpc::Service::MarkMethodGeneric(13); } ~WithGenericMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -1920,7 +2011,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondSetMode() { - ::grpc::Service::MarkMethodGeneric(13); + ::grpc::Service::MarkMethodGeneric(14); } ~WithGenericMethod_RespondSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -1937,7 +2028,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodGeneric(14); + ::grpc::Service::MarkMethodGeneric(15); } ~WithGenericMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1954,7 +2045,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodGeneric(15); + ::grpc::Service::MarkMethodGeneric(16); } ~WithGenericMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -1971,7 +2062,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodGeneric(16); + ::grpc::Service::MarkMethodGeneric(17); } ~WithGenericMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1988,7 +2079,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodGeneric(17); + ::grpc::Service::MarkMethodGeneric(18); } ~WithGenericMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2005,7 +2096,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodGeneric(18); + ::grpc::Service::MarkMethodGeneric(19); } ~WithGenericMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -2022,7 +2113,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodGeneric(19); + ::grpc::Service::MarkMethodGeneric(20); } ~WithGenericMethod_RespondFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -2039,7 +2130,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodGeneric(20); + ::grpc::Service::MarkMethodGeneric(21); } ~WithGenericMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -2056,7 +2147,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodGeneric(21); + ::grpc::Service::MarkMethodGeneric(22); } ~WithGenericMethod_RespondResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -2088,12 +2179,32 @@ class CameraServerService final { } }; template + class WithRawMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodRaw(1); + } + ~WithRawMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetInProgress() { - ::grpc::Service::MarkMethodRaw(1); + ::grpc::Service::MarkMethodRaw(2); } ~WithRawMethod_SetInProgress() override { BaseClassMustBeDerivedFromService(this); @@ -2104,7 +2215,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetInProgress(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2113,7 +2224,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodRaw(2); + ::grpc::Service::MarkMethodRaw(3); } ~WithRawMethod_SubscribeTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -2124,7 +2235,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeTakePhoto(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(2, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(3, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2133,7 +2244,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodRaw(3); + ::grpc::Service::MarkMethodRaw(4); } ~WithRawMethod_RespondTakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -2144,7 +2255,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondTakePhoto(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2153,7 +2264,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodRaw(4); + ::grpc::Service::MarkMethodRaw(5); } ~WithRawMethod_SubscribeStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2164,7 +2275,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(4, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2173,7 +2284,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodRaw(5); + ::grpc::Service::MarkMethodRaw(6); } ~WithRawMethod_RespondStartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2184,7 +2295,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStartVideo(::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(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2193,7 +2304,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(7); } ~WithRawMethod_SubscribeStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2204,7 +2315,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2213,7 +2324,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_RespondStopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2224,7 +2335,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStopVideo(::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(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2233,7 +2344,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(9); } ~WithRawMethod_SubscribeStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2244,7 +2355,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStartVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2253,7 +2364,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodRaw(9); + ::grpc::Service::MarkMethodRaw(10); } ~WithRawMethod_RespondStartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2264,7 +2375,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStartVideoStreaming(::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(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(10, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2273,7 +2384,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodRaw(10); + ::grpc::Service::MarkMethodRaw(11); } ~WithRawMethod_SubscribeStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2284,7 +2395,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2293,7 +2404,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodRaw(11); + ::grpc::Service::MarkMethodRaw(12); } ~WithRawMethod_RespondStopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2304,7 +2415,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStopVideoStreaming(::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(11, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(12, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2313,7 +2424,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodRaw(12); + ::grpc::Service::MarkMethodRaw(13); } ~WithRawMethod_SubscribeSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -2324,7 +2435,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeSetMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2333,7 +2444,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondSetMode() { - ::grpc::Service::MarkMethodRaw(13); + ::grpc::Service::MarkMethodRaw(14); } ~WithRawMethod_RespondSetMode() override { BaseClassMustBeDerivedFromService(this); @@ -2344,7 +2455,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondSetMode(::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(13, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(14, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2353,7 +2464,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodRaw(14); + ::grpc::Service::MarkMethodRaw(15); } ~WithRawMethod_SubscribeStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -2364,7 +2475,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStorageInformation(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2373,7 +2484,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodRaw(15); + ::grpc::Service::MarkMethodRaw(16); } ~WithRawMethod_RespondStorageInformation() override { BaseClassMustBeDerivedFromService(this); @@ -2384,7 +2495,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondStorageInformation(::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(15, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(16, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2393,7 +2504,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodRaw(16); + ::grpc::Service::MarkMethodRaw(17); } ~WithRawMethod_SubscribeCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2404,7 +2515,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2413,7 +2524,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodRaw(17); + ::grpc::Service::MarkMethodRaw(18); } ~WithRawMethod_RespondCaptureStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2424,7 +2535,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondCaptureStatus(::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(17, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(18, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2433,7 +2544,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodRaw(18); + ::grpc::Service::MarkMethodRaw(19); } ~WithRawMethod_SubscribeFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -2444,7 +2555,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFormatStorage(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2453,7 +2564,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodRaw(19); + ::grpc::Service::MarkMethodRaw(20); } ~WithRawMethod_RespondFormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -2464,7 +2575,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondFormatStorage(::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(19, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2473,7 +2584,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodRaw(20); + ::grpc::Service::MarkMethodRaw(21); } ~WithRawMethod_SubscribeResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -2484,7 +2595,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(21, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2493,7 +2604,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodRaw(21); + ::grpc::Service::MarkMethodRaw(22); } ~WithRawMethod_RespondResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -2504,7 +2615,7 @@ class CameraServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRespondResetSettings(::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(21, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2530,12 +2641,34 @@ class CameraServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodRawCallback(1, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetVideoStreaming(context, request, response); })); + } + ~WithRawCallbackMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetVideoStreaming( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetInProgress() { - ::grpc::Service::MarkMethodRawCallback(1, + ::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->SetInProgress(context, request, response); })); @@ -2557,7 +2690,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodRawCallback(2, + ::grpc::Service::MarkMethodRawCallback(3, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeTakePhoto(context, request); })); @@ -2579,7 +2712,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodRawCallback(3, + ::grpc::Service::MarkMethodRawCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondTakePhoto(context, request, response); })); @@ -2601,7 +2734,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodRawCallback(4, + ::grpc::Service::MarkMethodRawCallback(5, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideo(context, request); })); @@ -2623,7 +2756,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodRawCallback(5, + ::grpc::Service::MarkMethodRawCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStartVideo(context, request, response); })); @@ -2645,7 +2778,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodRawCallback(6, + ::grpc::Service::MarkMethodRawCallback(7, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideo(context, request); })); @@ -2667,7 +2800,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodRawCallback(7, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStopVideo(context, request, response); })); @@ -2689,7 +2822,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(8, + ::grpc::Service::MarkMethodRawCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStartVideoStreaming(context, request); })); @@ -2711,7 +2844,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(9, + ::grpc::Service::MarkMethodRawCallback(10, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStartVideoStreaming(context, request, response); })); @@ -2733,7 +2866,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(10, + ::grpc::Service::MarkMethodRawCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStopVideoStreaming(context, request); })); @@ -2755,7 +2888,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(11, + ::grpc::Service::MarkMethodRawCallback(12, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStopVideoStreaming(context, request, response); })); @@ -2777,7 +2910,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodRawCallback(12, + ::grpc::Service::MarkMethodRawCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeSetMode(context, request); })); @@ -2799,7 +2932,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondSetMode() { - ::grpc::Service::MarkMethodRawCallback(13, + ::grpc::Service::MarkMethodRawCallback(14, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondSetMode(context, request, response); })); @@ -2821,7 +2954,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodRawCallback(14, + ::grpc::Service::MarkMethodRawCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStorageInformation(context, request); })); @@ -2843,7 +2976,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodRawCallback(15, + ::grpc::Service::MarkMethodRawCallback(16, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondStorageInformation(context, request, response); })); @@ -2865,7 +2998,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodRawCallback(16, + ::grpc::Service::MarkMethodRawCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCaptureStatus(context, request); })); @@ -2887,7 +3020,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodRawCallback(17, + ::grpc::Service::MarkMethodRawCallback(18, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondCaptureStatus(context, request, response); })); @@ -2909,7 +3042,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodRawCallback(18, + ::grpc::Service::MarkMethodRawCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFormatStorage(context, request); })); @@ -2931,7 +3064,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodRawCallback(19, + ::grpc::Service::MarkMethodRawCallback(20, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondFormatStorage(context, request, response); })); @@ -2953,7 +3086,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodRawCallback(20, + ::grpc::Service::MarkMethodRawCallback(21, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeResetSettings(context, request); })); @@ -2975,7 +3108,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodRawCallback(21, + ::grpc::Service::MarkMethodRawCallback(22, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RespondResetSettings(context, request, response); })); @@ -3019,12 +3152,39 @@ class CameraServerService final { virtual ::grpc::Status StreamedSetInformation(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetInformationRequest,::mavsdk::rpc::camera_server::SetInformationResponse>* server_unary_streamer) = 0; }; template + class WithStreamedUnaryMethod_SetVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetVideoStreaming() { + ::grpc::Service::MarkMethodStreamed(1, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera_server::SetVideoStreamingRequest, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* streamer) { + return this->StreamedSetVideoStreaming(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetVideoStreaming(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest,::mavsdk::rpc::camera_server::SetVideoStreamingResponse>* server_unary_streamer) = 0; + }; + template class WithStreamedUnaryMethod_SetInProgress : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetInProgress() { - ::grpc::Service::MarkMethodStreamed(1, + ::grpc::Service::MarkMethodStreamed(2, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::SetInProgressRequest, ::mavsdk::rpc::camera_server::SetInProgressResponse>( [this](::grpc::ServerContext* context, @@ -3051,7 +3211,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondTakePhoto() { - ::grpc::Service::MarkMethodStreamed(3, + ::grpc::Service::MarkMethodStreamed(4, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondTakePhotoRequest, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>( [this](::grpc::ServerContext* context, @@ -3078,7 +3238,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStartVideo() { - ::grpc::Service::MarkMethodStreamed(5, + ::grpc::Service::MarkMethodStreamed(6, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoRequest, ::mavsdk::rpc::camera_server::RespondStartVideoResponse>( [this](::grpc::ServerContext* context, @@ -3105,7 +3265,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStopVideo() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoRequest, ::mavsdk::rpc::camera_server::RespondStopVideoResponse>( [this](::grpc::ServerContext* context, @@ -3132,7 +3292,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStartVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(9, + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -3159,7 +3319,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStopVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(11, + ::grpc::Service::MarkMethodStreamed(12, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -3186,7 +3346,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondSetMode() { - ::grpc::Service::MarkMethodStreamed(13, + ::grpc::Service::MarkMethodStreamed(14, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondSetModeRequest, ::mavsdk::rpc::camera_server::RespondSetModeResponse>( [this](::grpc::ServerContext* context, @@ -3213,7 +3373,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondStorageInformation() { - ::grpc::Service::MarkMethodStreamed(15, + ::grpc::Service::MarkMethodStreamed(16, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondStorageInformationRequest, ::mavsdk::rpc::camera_server::RespondStorageInformationResponse>( [this](::grpc::ServerContext* context, @@ -3240,7 +3400,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondCaptureStatus() { - ::grpc::Service::MarkMethodStreamed(17, + ::grpc::Service::MarkMethodStreamed(18, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondCaptureStatusRequest, ::mavsdk::rpc::camera_server::RespondCaptureStatusResponse>( [this](::grpc::ServerContext* context, @@ -3267,7 +3427,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondFormatStorage() { - ::grpc::Service::MarkMethodStreamed(19, + ::grpc::Service::MarkMethodStreamed(20, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondFormatStorageRequest, ::mavsdk::rpc::camera_server::RespondFormatStorageResponse>( [this](::grpc::ServerContext* context, @@ -3294,7 +3454,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RespondResetSettings() { - ::grpc::Service::MarkMethodStreamed(21, + ::grpc::Service::MarkMethodStreamed(22, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest, ::mavsdk::rpc::camera_server::RespondResetSettingsResponse>( [this](::grpc::ServerContext* context, @@ -3315,14 +3475,14 @@ class CameraServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedRespondResetSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera_server::RespondResetSettingsRequest,::mavsdk::rpc::camera_server::RespondResetSettingsResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeTakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeTakePhoto() { - ::grpc::Service::MarkMethodStreamed(2, + ::grpc::Service::MarkMethodStreamed(3, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest, ::mavsdk::rpc::camera_server::TakePhotoResponse>( [this](::grpc::ServerContext* context, @@ -3349,7 +3509,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStartVideo() { - ::grpc::Service::MarkMethodStreamed(4, + ::grpc::Service::MarkMethodStreamed(5, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoRequest, ::mavsdk::rpc::camera_server::StartVideoResponse>( [this](::grpc::ServerContext* context, @@ -3376,7 +3536,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStopVideo() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(7, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoRequest, ::mavsdk::rpc::camera_server::StopVideoResponse>( [this](::grpc::ServerContext* context, @@ -3403,7 +3563,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStartVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(9, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest, ::mavsdk::rpc::camera_server::StartVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -3430,7 +3590,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStopVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(10, + ::grpc::Service::MarkMethodStreamed(11, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest, ::mavsdk::rpc::camera_server::StopVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -3457,7 +3617,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeSetMode() { - ::grpc::Service::MarkMethodStreamed(12, + ::grpc::Service::MarkMethodStreamed(13, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeSetModeRequest, ::mavsdk::rpc::camera_server::SetModeResponse>( [this](::grpc::ServerContext* context, @@ -3484,7 +3644,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStorageInformation() { - ::grpc::Service::MarkMethodStreamed(14, + ::grpc::Service::MarkMethodStreamed(15, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest, ::mavsdk::rpc::camera_server::StorageInformationResponse>( [this](::grpc::ServerContext* context, @@ -3511,7 +3671,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeCaptureStatus() { - ::grpc::Service::MarkMethodStreamed(16, + ::grpc::Service::MarkMethodStreamed(17, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest, ::mavsdk::rpc::camera_server::CaptureStatusResponse>( [this](::grpc::ServerContext* context, @@ -3538,7 +3698,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeFormatStorage() { - ::grpc::Service::MarkMethodStreamed(18, + ::grpc::Service::MarkMethodStreamed(19, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest, ::mavsdk::rpc::camera_server::FormatStorageResponse>( [this](::grpc::ServerContext* context, @@ -3565,7 +3725,7 @@ class CameraServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeResetSettings() { - ::grpc::Service::MarkMethodStreamed(20, + ::grpc::Service::MarkMethodStreamed(21, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest, ::mavsdk::rpc::camera_server::ResetSettingsResponse>( [this](::grpc::ServerContext* context, @@ -3587,7 +3747,7 @@ class CameraServerService final { virtual ::grpc::Status StreamedSubscribeResetSettings(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest,::mavsdk::rpc::camera_server::ResetSettingsResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeTakePhoto > > > > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_SetInformation > > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace camera_server diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 16d40f225e..4d2a4415e9 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -54,6 +54,38 @@ struct SetInformationResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetInformationResponseDefaultTypeInternal _SetInformationResponse_default_instance_; template +PROTOBUF_CONSTEXPR SetVideoStreamingRequest::SetVideoStreamingRequest( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.video_streaming_)*/nullptr} {} +struct SetVideoStreamingRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetVideoStreamingRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetVideoStreamingRequestDefaultTypeInternal() {} + union { + SetVideoStreamingRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamingRequestDefaultTypeInternal _SetVideoStreamingRequest_default_instance_; +template +PROTOBUF_CONSTEXPR SetVideoStreamingResponse::SetVideoStreamingResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.camera_server_result_)*/nullptr} {} +struct SetVideoStreamingResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetVideoStreamingResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetVideoStreamingResponseDefaultTypeInternal() {} + union { + SetVideoStreamingResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetVideoStreamingResponseDefaultTypeInternal _SetVideoStreamingResponse_default_instance_; +template PROTOBUF_CONSTEXPR SetInProgressRequest::SetInProgressRequest( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.in_progress_)*/ false @@ -746,6 +778,26 @@ struct InformationDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 InformationDefaultTypeInternal _Information_default_instance_; template +PROTOBUF_CONSTEXPR VideoStreaming::VideoStreaming( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_.rtsp_uri_)*/ { + &::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized {} + } + + , /*decltype(_impl_.has_rtsp_server_)*/ false + + , /*decltype(_impl_._cached_size_)*/{}} {} +struct VideoStreamingDefaultTypeInternal { + PROTOBUF_CONSTEXPR VideoStreamingDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~VideoStreamingDefaultTypeInternal() {} + union { + VideoStreaming _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamingDefaultTypeInternal _VideoStreaming_default_instance_; +template PROTOBUF_CONSTEXPR Position::Position( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.latitude_deg_)*/ 0 @@ -895,7 +947,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[51]; +static ::_pb::Metadata file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[54]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto = nullptr; @@ -921,6 +973,26 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInformationResponse, _impl_.camera_server_result_), 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingRequest, _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::camera_server::SetVideoStreamingRequest, _impl_.video_streaming_), + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetVideoStreamingResponse, _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::camera_server::SetVideoStreamingResponse, _impl_.camera_server_result_), + 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::SetInProgressRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -1329,6 +1401,16 @@ const ::uint32_t TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets[ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, _impl_.definition_file_uri_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _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::camera_server::VideoStreaming, _impl_.has_rtsp_server_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::VideoStreaming, _impl_.rtsp_uri_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1418,60 +1500,65 @@ static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { { 0, 9, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationRequest)}, { 10, 19, -1, sizeof(::mavsdk::rpc::camera_server::SetInformationResponse)}, - { 20, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressRequest)}, - { 29, 38, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, - { 39, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, - { 47, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, - { 56, 66, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, - { 68, 77, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, - { 78, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, - { 86, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, - { 95, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoRequest)}, - { 104, 113, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoResponse)}, - { 114, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, - { 122, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, - { 131, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoRequest)}, - { 140, 149, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoResponse)}, - { 150, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, - { 158, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, - { 167, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest)}, - { 176, 185, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse)}, - { 186, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, - { 194, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, - { 203, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest)}, - { 212, 221, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse)}, - { 222, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, - { 230, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, - { 239, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeRequest)}, - { 248, 257, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeResponse)}, - { 258, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, - { 266, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, - { 275, 285, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, - { 287, 296, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, - { 297, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, - { 305, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, - { 314, 324, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, - { 326, 335, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, - { 336, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, - { 344, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, - { 353, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageRequest)}, - { 362, 371, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageResponse)}, - { 372, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, - { 380, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, - { 389, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, - { 398, 407, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, - { 408, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 427, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 439, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 451, 465, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 471, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, - { 481, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, - { 497, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, + { 20, 29, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamingRequest)}, + { 30, 39, -1, sizeof(::mavsdk::rpc::camera_server::SetVideoStreamingResponse)}, + { 40, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressRequest)}, + { 49, 58, -1, sizeof(::mavsdk::rpc::camera_server::SetInProgressResponse)}, + { 59, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest)}, + { 67, -1, -1, sizeof(::mavsdk::rpc::camera_server::TakePhotoResponse)}, + { 76, 86, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, + { 88, 97, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, + { 98, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoRequest)}, + { 106, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoResponse)}, + { 115, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoRequest)}, + { 124, 133, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoResponse)}, + { 134, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoRequest)}, + { 142, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoResponse)}, + { 151, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoRequest)}, + { 160, 169, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoResponse)}, + { 170, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStartVideoStreamingRequest)}, + { 178, -1, -1, sizeof(::mavsdk::rpc::camera_server::StartVideoStreamingResponse)}, + { 187, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingRequest)}, + { 196, 205, -1, sizeof(::mavsdk::rpc::camera_server::RespondStartVideoStreamingResponse)}, + { 206, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStopVideoStreamingRequest)}, + { 214, -1, -1, sizeof(::mavsdk::rpc::camera_server::StopVideoStreamingResponse)}, + { 223, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingRequest)}, + { 232, 241, -1, sizeof(::mavsdk::rpc::camera_server::RespondStopVideoStreamingResponse)}, + { 242, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeSetModeRequest)}, + { 250, -1, -1, sizeof(::mavsdk::rpc::camera_server::SetModeResponse)}, + { 259, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeRequest)}, + { 268, 277, -1, sizeof(::mavsdk::rpc::camera_server::RespondSetModeResponse)}, + { 278, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeStorageInformationRequest)}, + { 286, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformationResponse)}, + { 295, 305, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationRequest)}, + { 307, 316, -1, sizeof(::mavsdk::rpc::camera_server::RespondStorageInformationResponse)}, + { 317, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeCaptureStatusRequest)}, + { 325, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatusResponse)}, + { 334, 344, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusRequest)}, + { 346, 355, -1, sizeof(::mavsdk::rpc::camera_server::RespondCaptureStatusResponse)}, + { 356, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeFormatStorageRequest)}, + { 364, -1, -1, sizeof(::mavsdk::rpc::camera_server::FormatStorageResponse)}, + { 373, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageRequest)}, + { 382, 391, -1, sizeof(::mavsdk::rpc::camera_server::RespondFormatStorageResponse)}, + { 392, -1, -1, sizeof(::mavsdk::rpc::camera_server::SubscribeResetSettingsRequest)}, + { 400, -1, -1, sizeof(::mavsdk::rpc::camera_server::ResetSettingsResponse)}, + { 409, -1, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsRequest)}, + { 418, 427, -1, sizeof(::mavsdk::rpc::camera_server::RespondResetSettingsResponse)}, + { 428, -1, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, + { 447, -1, -1, sizeof(::mavsdk::rpc::camera_server::VideoStreaming)}, + { 457, -1, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 469, -1, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 481, 495, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 501, -1, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 511, -1, -1, sizeof(::mavsdk::rpc::camera_server::StorageInformation)}, + { 527, -1, -1, sizeof(::mavsdk::rpc::camera_server::CaptureStatus)}, }; static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_SetInformationRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInformationResponse_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SetVideoStreamingRequest_default_instance_._instance, + &::mavsdk::rpc::camera_server::_SetVideoStreamingResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInProgressRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_SetInProgressResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_SubscribeTakePhotoRequest_default_instance_._instance, @@ -1515,6 +1602,7 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera_server::_RespondResetSettingsRequest_default_instance_._instance, &::mavsdk::rpc::camera_server::_RespondResetSettingsResponse_default_instance_._instance, &::mavsdk::rpc::camera_server::_Information_default_instance_._instance, + &::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_._instance, &::mavsdk::rpc::camera_server::_Position_default_instance_._instance, &::mavsdk::rpc::camera_server::_Quaternion_default_instance_._instance, &::mavsdk::rpc::camera_server::_CaptureInfo_default_instance_._instance, @@ -1529,6 +1617,11 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "ion\030\001 \001(\0132%.mavsdk.rpc.camera_server.Inf" "ormation\"d\n\026SetInformationResponse\022J\n\024ca" "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" + "mera_server.CameraServerResult\"]\n\030SetVid" + "eoStreamingRequest\022A\n\017video_streaming\030\001 " + "\001(\0132(.mavsdk.rpc.camera_server.VideoStre" + "aming\"g\n\031SetVideoStreamingResponse\022J\n\024ca" + "mera_server_result\030\001 \001(\0132,.mavsdk.rpc.ca" "mera_server.CameraServerResult\"+\n\024SetInP" "rogressRequest\022\023\n\013in_progress\030\001 \001(\010\"c\n\025S" "etInProgressResponse\022J\n\024camera_server_re" @@ -1619,136 +1712,141 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\030\006 \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r" "\022\036\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens" "_id\030\t \001(\r\022\037\n\027definition_file_version\030\n \001" - "(\r\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Posit" - "ion\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_d" - "eg\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n" - "\023relative_altitude_m\030\004 \001(\002\"8\n\nQuaternion" - "\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004" - " \001(\002\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\"" - ".mavsdk.rpc.camera_server.Position\022A\n\023at" - "titude_quaternion\030\002 \001(\0132$.mavsdk.rpc.cam" - "era_server.Quaternion\022\023\n\013time_utc_us\030\003 \001" - "(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n" - "\010file_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C" - "\n\006result\030\001 \001(\01623.mavsdk.rpc.camera_serve" - "r.CameraServerResult.Result\022\022\n\nresult_st" - "r\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022" - "\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS" - "\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020" - "\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025" - "RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYS" - "TEM\020\010\"\214\005\n\022StorageInformation\022\030\n\020used_sto" - "rage_mib\030\001 \001(\002\022\035\n\025available_storage_mib\030" - "\002 \001(\002\022\031\n\021total_storage_mib\030\003 \001(\002\022R\n\016stor" - "age_status\030\004 \001(\0162:.mavsdk.rpc.camera_ser" - "ver.StorageInformation.StorageStatus\022\022\n\n" - "storage_id\030\005 \001(\r\022N\n\014storage_type\030\006 \001(\01628" - ".mavsdk.rpc.camera_server.StorageInforma" - "tion.StorageType\022\030\n\020read_speed_mib_s\030\007 \001" - "(\002\022\031\n\021write_speed_mib_s\030\010 \001(\002\"\221\001\n\rStorag" - "eStatus\022 \n\034STORAGE_STATUS_NOT_AVAILABLE\020" - "\000\022\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STO" - "RAGE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STATU" - "S_NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STO" - "RAGE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_" - "STICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_" - "TYPE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022S" - "TORAGE_TYPE_OTHER\020\376\001\"\356\003\n\rCaptureStatus\022\030" - "\n\020image_interval_s\030\001 \001(\002\022\030\n\020recording_ti" - "me_s\030\002 \001(\002\022\036\n\026available_capacity_mib\030\003 \001" - "(\002\022I\n\014image_status\030\004 \001(\01623.mavsdk.rpc.ca" - "mera_server.CaptureStatus.ImageStatus\022I\n" - "\014video_status\030\005 \001(\01623.mavsdk.rpc.camera_" - "server.CaptureStatus.VideoStatus\022\023\n\013imag" - "e_count\030\006 \001(\005\"\221\001\n\013ImageStatus\022\025\n\021IMAGE_S" - "TATUS_IDLE\020\000\022$\n IMAGE_STATUS_CAPTURE_IN_" - "PROGRESS\020\001\022\036\n\032IMAGE_STATUS_INTERVAL_IDLE" - "\020\002\022%\n!IMAGE_STATUS_INTERVAL_IN_PROGRESS\020" - "\003\"J\n\013VideoStatus\022\025\n\021VIDEO_STATUS_IDLE\020\000\022" - "$\n VIDEO_STATUS_CAPTURE_IN_PROGRESS\020\001*{\n" - "\016CameraFeedback\022\033\n\027CAMERA_FEEDBACK_UNKNO" - "WN\020\000\022\026\n\022CAMERA_FEEDBACK_OK\020\001\022\030\n\024CAMERA_F" - "EEDBACK_BUSY\020\002\022\032\n\026CAMERA_FEEDBACK_FAILED" - "\020\003*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE_PHO" - "TO\020\001\022\016\n\nMODE_VIDEO\020\0022\212\030\n\023CameraServerSer" - "vice\022y\n\016SetInformation\022/.mavsdk.rpc.came" - "ra_server.SetInformationRequest\0320.mavsdk" - ".rpc.camera_server.SetInformationRespons" - "e\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.ca" - "mera_server.SetInProgressRequest\032/.mavsd" - "k.rpc.camera_server.SetInProgressRespons" - "e\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.r" - "pc.camera_server.SubscribeTakePhotoReque" - "st\032+.mavsdk.rpc.camera_server.TakePhotoR" - "esponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.ma" - "vsdk.rpc.camera_server.RespondTakePhotoR" - "equest\0322.mavsdk.rpc.camera_server.Respon" - "dTakePhotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeSt" - "artVideo\0224.mavsdk.rpc.camera_server.Subs" - "cribeStartVideoRequest\032,.mavsdk.rpc.came" - "ra_server.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n" - "\021RespondStartVideo\0222.mavsdk.rpc.camera_s" - "erver.RespondStartVideoRequest\0323.mavsdk." - "rpc.camera_server.RespondStartVideoRespo" - "nse\"\004\200\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk" - ".rpc.camera_server.SubscribeStopVideoReq" - "uest\032+.mavsdk.rpc.camera_server.StopVide" - "oResponse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221." - "mavsdk.rpc.camera_server.RespondStopVide" - "oRequest\0322.mavsdk.rpc.camera_server.Resp" - "ondStopVideoResponse\"\004\200\265\030\001\022\234\001\n\034Subscribe" - "StartVideoStreaming\022=.mavsdk.rpc.camera_" - "server.SubscribeStartVideoStreamingReque" - "st\0325.mavsdk.rpc.camera_server.StartVideo" - "StreamingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondSta" - "rtVideoStreaming\022;.mavsdk.rpc.camera_ser" - "ver.RespondStartVideoStreamingRequest\032<." - "mavsdk.rpc.camera_server.RespondStartVid" - "eoStreamingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeS" - "topVideoStreaming\022<.mavsdk.rpc.camera_se" - "rver.SubscribeStopVideoStreamingRequest\032" - "4.mavsdk.rpc.camera_server.StopVideoStre" - "amingResponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVid" - "eoStreaming\022:.mavsdk.rpc.camera_server.R" - "espondStopVideoStreamingRequest\032;.mavsdk" - ".rpc.camera_server.RespondStopVideoStrea" - "mingResponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221" - ".mavsdk.rpc.camera_server.SubscribeSetMo" - "deRequest\032).mavsdk.rpc.camera_server.Set" - "ModeResponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/" - ".mavsdk.rpc.camera_server.RespondSetMode" - "Request\0320.mavsdk.rpc.camera_server.Respo" - "ndSetModeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeSto" - "rageInformation\022<.mavsdk.rpc.camera_serv" - "er.SubscribeStorageInformationRequest\0324." + "(\r\022\033\n\023definition_file_uri\030\013 \001(\t\";\n\016Video" + "Streaming\022\027\n\017has_rtsp_server\030\001 \001(\010\022\020\n\010rt" + "sp_uri\030\002 \001(\t\"q\n\010Position\022\024\n\014latitude_deg" + "\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolut" + "e_altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_" + "m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 " + "\001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInf" + "o\0224\n\010position\030\001 \001(\0132\".mavsdk.rpc.camera_" + "server.Position\022A\n\023attitude_quaternion\030\002" + " \001(\0132$.mavsdk.rpc.camera_server.Quaterni" + "on\022\023\n\013time_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 " + "\001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n" + "\022CameraServerResult\022C\n\006result\030\001 \001(\01623.ma" + "vsdk.rpc.camera_server.CameraServerResul" + "t.Result\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022" + "\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022" + "\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003" + "\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n" + "\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUME" + "NT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\"\214\005\n\022StorageIn" + "formation\022\030\n\020used_storage_mib\030\001 \001(\002\022\035\n\025a" + "vailable_storage_mib\030\002 \001(\002\022\031\n\021total_stor" + "age_mib\030\003 \001(\002\022R\n\016storage_status\030\004 \001(\0162:." "mavsdk.rpc.camera_server.StorageInformat" - "ionResponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageIn" - "formation\022:.mavsdk.rpc.camera_server.Res" - "pondStorageInformationRequest\032;.mavsdk.r" - "pc.camera_server.RespondStorageInformati" - "onResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureSta" - "tus\0227.mavsdk.rpc.camera_server.Subscribe" - "CaptureStatusRequest\032/.mavsdk.rpc.camera" - "_server.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001" - "\n\024RespondCaptureStatus\0225.mavsdk.rpc.came" - "ra_server.RespondCaptureStatusRequest\0326." - "mavsdk.rpc.camera_server.RespondCaptureS" - "tatusResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatS" - "torage\0227.mavsdk.rpc.camera_server.Subscr" - "ibeFormatStorageRequest\032/.mavsdk.rpc.cam" - "era_server.FormatStorageResponse\"\004\200\265\030\0000\001" - "\022\213\001\n\024RespondFormatStorage\0225.mavsdk.rpc.c" - "amera_server.RespondFormatStorageRequest" - "\0326.mavsdk.rpc.camera_server.RespondForma" - "tStorageResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeRese" - "tSettings\0227.mavsdk.rpc.camera_server.Sub" - "scribeResetSettingsRequest\032/.mavsdk.rpc." - "camera_server.ResetSettingsResponse\"\004\200\265\030" - "\0000\001\022\213\001\n\024RespondResetSettings\0225.mavsdk.rp" - "c.camera_server.RespondResetSettingsRequ" - "est\0326.mavsdk.rpc.camera_server.RespondRe" - "setSettingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.c" - "amera_serverB\021CameraServerProtob\006proto3" + "ion.StorageStatus\022\022\n\nstorage_id\030\005 \001(\r\022N\n" + "\014storage_type\030\006 \001(\01628.mavsdk.rpc.camera_" + "server.StorageInformation.StorageType\022\030\n" + "\020read_speed_mib_s\030\007 \001(\002\022\031\n\021write_speed_m" + "ib_s\030\010 \001(\002\"\221\001\n\rStorageStatus\022 \n\034STORAGE_" + "STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS" + "_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATT" + "ED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240" + "\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000" + "\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_" + "TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017S" + "TORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376" + "\001\"\356\003\n\rCaptureStatus\022\030\n\020image_interval_s\030" + "\001 \001(\002\022\030\n\020recording_time_s\030\002 \001(\002\022\036\n\026avail" + "able_capacity_mib\030\003 \001(\002\022I\n\014image_status\030" + "\004 \001(\01623.mavsdk.rpc.camera_server.Capture" + "Status.ImageStatus\022I\n\014video_status\030\005 \001(\016" + "23.mavsdk.rpc.camera_server.CaptureStatu" + "s.VideoStatus\022\023\n\013image_count\030\006 \001(\005\"\221\001\n\013I" + "mageStatus\022\025\n\021IMAGE_STATUS_IDLE\020\000\022$\n IMA" + "GE_STATUS_CAPTURE_IN_PROGRESS\020\001\022\036\n\032IMAGE" + "_STATUS_INTERVAL_IDLE\020\002\022%\n!IMAGE_STATUS_" + "INTERVAL_IN_PROGRESS\020\003\"J\n\013VideoStatus\022\025\n" + "\021VIDEO_STATUS_IDLE\020\000\022$\n VIDEO_STATUS_CAP" + "TURE_IN_PROGRESS\020\001*{\n\016CameraFeedback\022\033\n\027" + "CAMERA_FEEDBACK_UNKNOWN\020\000\022\026\n\022CAMERA_FEED" + "BACK_OK\020\001\022\030\n\024CAMERA_FEEDBACK_BUSY\020\002\022\032\n\026C" + "AMERA_FEEDBACK_FAILED\020\003*8\n\004Mode\022\020\n\014MODE_" + "UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020" + "\0022\217\031\n\023CameraServerService\022y\n\016SetInformat" + "ion\022/.mavsdk.rpc.camera_server.SetInform" + "ationRequest\0320.mavsdk.rpc.camera_server." + "SetInformationResponse\"\004\200\265\030\001\022\202\001\n\021SetVide" + "oStreaming\0222.mavsdk.rpc.camera_server.Se" + "tVideoStreamingRequest\0323.mavsdk.rpc.came" + "ra_server.SetVideoStreamingResponse\"\004\200\265\030" + "\001\022v\n\rSetInProgress\022..mavsdk.rpc.camera_s" + "erver.SetInProgressRequest\032/.mavsdk.rpc." + "camera_server.SetInProgressResponse\"\004\200\265\030" + "\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rpc.cam" + "era_server.SubscribeTakePhotoRequest\032+.m" + "avsdk.rpc.camera_server.TakePhotoRespons" + "e\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mavsdk.r" + "pc.camera_server.RespondTakePhotoRequest" + "\0322.mavsdk.rpc.camera_server.RespondTakeP" + "hotoResponse\"\004\200\265\030\001\022\201\001\n\023SubscribeStartVid" + "eo\0224.mavsdk.rpc.camera_server.SubscribeS" + "tartVideoRequest\032,.mavsdk.rpc.camera_ser" + "ver.StartVideoResponse\"\004\200\265\030\0000\001\022\202\001\n\021Respo" + "ndStartVideo\0222.mavsdk.rpc.camera_server." + "RespondStartVideoRequest\0323.mavsdk.rpc.ca" + "mera_server.RespondStartVideoResponse\"\004\200" + "\265\030\001\022~\n\022SubscribeStopVideo\0223.mavsdk.rpc.c" + "amera_server.SubscribeStopVideoRequest\032+" + ".mavsdk.rpc.camera_server.StopVideoRespo" + "nse\"\004\200\265\030\0000\001\022\177\n\020RespondStopVideo\0221.mavsdk" + ".rpc.camera_server.RespondStopVideoReque" + "st\0322.mavsdk.rpc.camera_server.RespondSto" + "pVideoResponse\"\004\200\265\030\001\022\234\001\n\034SubscribeStartV" + "ideoStreaming\022=.mavsdk.rpc.camera_server" + ".SubscribeStartVideoStreamingRequest\0325.m" + "avsdk.rpc.camera_server.StartVideoStream" + "ingResponse\"\004\200\265\030\0000\001\022\235\001\n\032RespondStartVide" + "oStreaming\022;.mavsdk.rpc.camera_server.Re" + "spondStartVideoStreamingRequest\032<.mavsdk" + ".rpc.camera_server.RespondStartVideoStre" + "amingResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStopVid" + "eoStreaming\022<.mavsdk.rpc.camera_server.S" + "ubscribeStopVideoStreamingRequest\0324.mavs" + "dk.rpc.camera_server.StopVideoStreamingR" + "esponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStopVideoStre" + "aming\022:.mavsdk.rpc.camera_server.Respond" + "StopVideoStreamingRequest\032;.mavsdk.rpc.c" + "amera_server.RespondStopVideoStreamingRe" + "sponse\"\004\200\265\030\001\022x\n\020SubscribeSetMode\0221.mavsd" + "k.rpc.camera_server.SubscribeSetModeRequ" + "est\032).mavsdk.rpc.camera_server.SetModeRe" + "sponse\"\004\200\265\030\0000\001\022y\n\016RespondSetMode\022/.mavsd" + "k.rpc.camera_server.RespondSetModeReques" + "t\0320.mavsdk.rpc.camera_server.RespondSetM" + "odeResponse\"\004\200\265\030\001\022\231\001\n\033SubscribeStorageIn" + "formation\022<.mavsdk.rpc.camera_server.Sub" + "scribeStorageInformationRequest\0324.mavsdk" + ".rpc.camera_server.StorageInformationRes" + "ponse\"\004\200\265\030\0000\001\022\232\001\n\031RespondStorageInformat" + "ion\022:.mavsdk.rpc.camera_server.RespondSt" + "orageInformationRequest\032;.mavsdk.rpc.cam" + "era_server.RespondStorageInformationResp" + "onse\"\004\200\265\030\001\022\212\001\n\026SubscribeCaptureStatus\0227." + "mavsdk.rpc.camera_server.SubscribeCaptur" + "eStatusRequest\032/.mavsdk.rpc.camera_serve" + "r.CaptureStatusResponse\"\004\200\265\030\0000\001\022\213\001\n\024Resp" + "ondCaptureStatus\0225.mavsdk.rpc.camera_ser" + "ver.RespondCaptureStatusRequest\0326.mavsdk" + ".rpc.camera_server.RespondCaptureStatusR" + "esponse\"\004\200\265\030\001\022\212\001\n\026SubscribeFormatStorage" + "\0227.mavsdk.rpc.camera_server.SubscribeFor" + "matStorageRequest\032/.mavsdk.rpc.camera_se" + "rver.FormatStorageResponse\"\004\200\265\030\0000\001\022\213\001\n\024R" + "espondFormatStorage\0225.mavsdk.rpc.camera_" + "server.RespondFormatStorageRequest\0326.mav" + "sdk.rpc.camera_server.RespondFormatStora" + "geResponse\"\004\200\265\030\001\022\212\001\n\026SubscribeResetSetti" + "ngs\0227.mavsdk.rpc.camera_server.Subscribe" + "ResetSettingsRequest\032/.mavsdk.rpc.camera" + "_server.ResetSettingsResponse\"\004\200\265\030\0000\001\022\213\001" + "\n\024RespondResetSettings\0225.mavsdk.rpc.came" + "ra_server.RespondResetSettingsRequest\0326." + "mavsdk.rpc.camera_server.RespondResetSet" + "tingsResponse\"\004\200\265\030\001B,\n\027io.mavsdk.camera_" + "serverB\021CameraServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { @@ -1758,13 +1856,13 @@ static ::absl::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2epr const ::_pbi::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { false, false, - 9039, + 9433, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, - 51, + 54, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, @@ -2384,6 +2482,416 @@ ::PROTOBUF_NAMESPACE_ID::Metadata SetInformationResponse::GetMetadata() const { } // =================================================================== +class SetVideoStreamingRequest::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(SetVideoStreamingRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::VideoStreaming& video_streaming(const SetVideoStreamingRequest* msg); + static void set_has_video_streaming(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::VideoStreaming& +SetVideoStreamingRequest::_Internal::video_streaming(const SetVideoStreamingRequest* msg) { + return *msg->_impl_.video_streaming_; +} +SetVideoStreamingRequest::SetVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +} +SetVideoStreamingRequest::SetVideoStreamingRequest(const SetVideoStreamingRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + SetVideoStreamingRequest* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.video_streaming_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.video_streaming_ = new ::mavsdk::rpc::camera_server::VideoStreaming(*from._impl_.video_streaming_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) +} + +inline void SetVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.video_streaming_){nullptr} + }; +} + +SetVideoStreamingRequest::~SetVideoStreamingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetVideoStreamingRequest::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.video_streaming_; +} + +void SetVideoStreamingRequest::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetVideoStreamingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.video_streaming_ != nullptr); + _impl_.video_streaming_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetVideoStreamingRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_video_streaming(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetVideoStreamingRequest::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::video_streaming(this), + _Internal::video_streaming(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.SetVideoStreamingRequest) + return target; +} + +::size_t SetVideoStreamingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.video_streaming_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetVideoStreamingRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetVideoStreamingRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetVideoStreamingRequest::GetClassData() const { return &_class_data_; } + + +void SetVideoStreamingRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.SetVideoStreamingRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_video_streaming()->::mavsdk::rpc::camera_server::VideoStreaming::MergeFrom( + from._internal_video_streaming()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetVideoStreamingRequest::CopyFrom(const SetVideoStreamingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetVideoStreamingRequest::IsInitialized() const { + return true; +} + +void SetVideoStreamingRequest::InternalSwap(SetVideoStreamingRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.video_streaming_, other->_impl_.video_streaming_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetVideoStreamingRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[2]); +} +// =================================================================== + +class SetVideoStreamingResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(SetVideoStreamingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result(const SetVideoStreamingResponse* msg); + static void set_has_camera_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera_server::CameraServerResult& +SetVideoStreamingResponse::_Internal::camera_server_result(const SetVideoStreamingResponse* msg) { + return *msg->_impl_.camera_server_result_; +} +SetVideoStreamingResponse::SetVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +} +SetVideoStreamingResponse::SetVideoStreamingResponse(const SetVideoStreamingResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + SetVideoStreamingResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.camera_server_result_ = new ::mavsdk::rpc::camera_server::CameraServerResult(*from._impl_.camera_server_result_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) +} + +inline void SetVideoStreamingResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.camera_server_result_){nullptr} + }; +} + +SetVideoStreamingResponse::~SetVideoStreamingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetVideoStreamingResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.camera_server_result_; +} + +void SetVideoStreamingResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void SetVideoStreamingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_server_result_ != nullptr); + _impl_.camera_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetVideoStreamingResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_camera_server_result(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* SetVideoStreamingResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::camera_server_result(this), + _Internal::camera_server_result(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.SetVideoStreamingResponse) + return target; +} + +::size_t SetVideoStreamingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.camera_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetVideoStreamingResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + SetVideoStreamingResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetVideoStreamingResponse::GetClassData() const { return &_class_data_; } + + +void SetVideoStreamingResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.SetVideoStreamingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_server_result()->::mavsdk::rpc::camera_server::CameraServerResult::MergeFrom( + from._internal_camera_server_result()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetVideoStreamingResponse::CopyFrom(const SetVideoStreamingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetVideoStreamingResponse::IsInitialized() const { + return true; +} + +void SetVideoStreamingResponse::InternalSwap(SetVideoStreamingResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.camera_server_result_, other->_impl_.camera_server_result_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata SetVideoStreamingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[3]); +} +// =================================================================== + class SetInProgressRequest::_Internal { public: }; @@ -2553,7 +3061,7 @@ void SetInProgressRequest::InternalSwap(SetInProgressRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SetInProgressRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[2]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[4]); } // =================================================================== @@ -2758,7 +3266,7 @@ void SetInProgressResponse::InternalSwap(SetInProgressResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SetInProgressResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[3]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[5]); } // =================================================================== @@ -2796,7 +3304,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeTakePhotoRequest::Get ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[4]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); } // =================================================================== @@ -2970,7 +3478,7 @@ void TakePhotoResponse::InternalSwap(TakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata TakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[5]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); } // =================================================================== @@ -3212,7 +3720,7 @@ void RespondTakePhotoRequest::InternalSwap(RespondTakePhotoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[6]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); } // =================================================================== @@ -3417,7 +3925,7 @@ void RespondTakePhotoResponse::InternalSwap(RespondTakePhotoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondTakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[7]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); } // =================================================================== @@ -3455,7 +3963,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoRequest::Ge ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[8]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); } // =================================================================== @@ -3629,7 +4137,7 @@ void StartVideoResponse::InternalSwap(StartVideoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata StartVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[9]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); } // =================================================================== @@ -3803,7 +4311,7 @@ void RespondStartVideoRequest::InternalSwap(RespondStartVideoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[10]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); } // =================================================================== @@ -4008,7 +4516,7 @@ void RespondStartVideoResponse::InternalSwap(RespondStartVideoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[11]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); } // =================================================================== @@ -4046,7 +4554,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoRequest::Get ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[12]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); } // =================================================================== @@ -4220,7 +4728,7 @@ void StopVideoResponse::InternalSwap(StopVideoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata StopVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[13]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); } // =================================================================== @@ -4394,7 +4902,7 @@ void RespondStopVideoRequest::InternalSwap(RespondStopVideoRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[14]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); } // =================================================================== @@ -4599,7 +5107,7 @@ void RespondStopVideoResponse::InternalSwap(RespondStopVideoResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[15]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); } // =================================================================== @@ -4637,7 +5145,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStartVideoStreamingRe ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStartVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[16]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); } // =================================================================== @@ -4811,7 +5319,7 @@ void StartVideoStreamingResponse::InternalSwap(StartVideoStreamingResponse* othe ::PROTOBUF_NAMESPACE_ID::Metadata StartVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[17]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); } // =================================================================== @@ -4985,7 +5493,7 @@ void RespondStartVideoStreamingRequest::InternalSwap(RespondStartVideoStreamingR ::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[18]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); } // =================================================================== @@ -5190,7 +5698,7 @@ void RespondStartVideoStreamingResponse::InternalSwap(RespondStartVideoStreaming ::PROTOBUF_NAMESPACE_ID::Metadata RespondStartVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[19]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); } // =================================================================== @@ -5228,7 +5736,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStopVideoStreamingReq ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStopVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[20]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); } // =================================================================== @@ -5402,7 +5910,7 @@ void StopVideoStreamingResponse::InternalSwap(StopVideoStreamingResponse* other) ::PROTOBUF_NAMESPACE_ID::Metadata StopVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[21]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]); } // =================================================================== @@ -5576,7 +6084,7 @@ void RespondStopVideoStreamingRequest::InternalSwap(RespondStopVideoStreamingReq ::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[22]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); } // =================================================================== @@ -5781,7 +6289,7 @@ void RespondStopVideoStreamingResponse::InternalSwap(RespondStopVideoStreamingRe ::PROTOBUF_NAMESPACE_ID::Metadata RespondStopVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[23]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); } // =================================================================== @@ -5819,7 +6327,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeSetModeRequest::GetCl ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeSetModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[24]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); } // =================================================================== @@ -5993,7 +6501,7 @@ void SetModeResponse::InternalSwap(SetModeResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata SetModeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[25]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); } // =================================================================== @@ -6167,7 +6675,7 @@ void RespondSetModeRequest::InternalSwap(RespondSetModeRequest* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondSetModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[26]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); } // =================================================================== @@ -6372,7 +6880,7 @@ void RespondSetModeResponse::InternalSwap(RespondSetModeResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata RespondSetModeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[27]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); } // =================================================================== @@ -6410,7 +6918,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeStorageInformationReq ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeStorageInformationRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[28]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); } // =================================================================== @@ -6584,7 +7092,7 @@ void StorageInformationResponse::InternalSwap(StorageInformationResponse* other) ::PROTOBUF_NAMESPACE_ID::Metadata StorageInformationResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[29]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); } // =================================================================== @@ -6826,7 +7334,7 @@ void RespondStorageInformationRequest::InternalSwap(RespondStorageInformationReq ::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[30]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); } // =================================================================== @@ -7031,7 +7539,7 @@ void RespondStorageInformationResponse::InternalSwap(RespondStorageInformationRe ::PROTOBUF_NAMESPACE_ID::Metadata RespondStorageInformationResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[31]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]); } // =================================================================== @@ -7069,7 +7577,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeCaptureStatusRequest: ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeCaptureStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[32]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[34]); } // =================================================================== @@ -7243,7 +7751,7 @@ void CaptureStatusResponse::InternalSwap(CaptureStatusResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[33]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[35]); } // =================================================================== @@ -7485,7 +7993,7 @@ void RespondCaptureStatusRequest::InternalSwap(RespondCaptureStatusRequest* othe ::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[34]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[36]); } // =================================================================== @@ -7690,7 +8198,7 @@ void RespondCaptureStatusResponse::InternalSwap(RespondCaptureStatusResponse* ot ::PROTOBUF_NAMESPACE_ID::Metadata RespondCaptureStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[35]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[37]); } // =================================================================== @@ -7728,7 +8236,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeFormatStorageRequest: ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeFormatStorageRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[36]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[38]); } // =================================================================== @@ -7902,7 +8410,7 @@ void FormatStorageResponse::InternalSwap(FormatStorageResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata FormatStorageResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[37]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[39]); } // =================================================================== @@ -8076,7 +8584,7 @@ void RespondFormatStorageRequest::InternalSwap(RespondFormatStorageRequest* othe ::PROTOBUF_NAMESPACE_ID::Metadata RespondFormatStorageRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[38]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[40]); } // =================================================================== @@ -8281,7 +8789,7 @@ void RespondFormatStorageResponse::InternalSwap(RespondFormatStorageResponse* ot ::PROTOBUF_NAMESPACE_ID::Metadata RespondFormatStorageResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[39]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[41]); } // =================================================================== @@ -8319,7 +8827,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeResetSettingsRequest: ::PROTOBUF_NAMESPACE_ID::Metadata SubscribeResetSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[40]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[42]); } // =================================================================== @@ -8493,7 +9001,7 @@ void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ResetSettingsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[41]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[43]); } // =================================================================== @@ -8667,7 +9175,7 @@ void RespondResetSettingsRequest::InternalSwap(RespondResetSettingsRequest* othe ::PROTOBUF_NAMESPACE_ID::Metadata RespondResetSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[42]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[44]); } // =================================================================== @@ -8872,7 +9380,7 @@ void RespondResetSettingsResponse::InternalSwap(RespondResetSettingsResponse* ot ::PROTOBUF_NAMESPACE_ID::Metadata RespondResetSettingsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[43]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[45]); } // =================================================================== @@ -9457,7 +9965,235 @@ void Information::InternalSwap(Information* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Information::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[44]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[46]); +} +// =================================================================== + +class VideoStreaming::_Internal { + public: +}; + +VideoStreaming::VideoStreaming(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera_server.VideoStreaming) +} +VideoStreaming::VideoStreaming(const VideoStreaming& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + VideoStreaming* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.rtsp_uri_) {} + + , decltype(_impl_.has_rtsp_server_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.rtsp_uri_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.rtsp_uri_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_rtsp_uri().empty()) { + _this->_impl_.rtsp_uri_.Set(from._internal_rtsp_uri(), _this->GetArenaForAllocation()); + } + _this->_impl_.has_rtsp_server_ = from._impl_.has_rtsp_server_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.VideoStreaming) +} + +inline void VideoStreaming::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.rtsp_uri_) {} + + , decltype(_impl_.has_rtsp_server_) { false } + + , /*decltype(_impl_._cached_size_)*/{} + }; + _impl_.rtsp_uri_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.rtsp_uri_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING +} + +VideoStreaming::~VideoStreaming() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera_server.VideoStreaming) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void VideoStreaming::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.rtsp_uri_.Destroy(); +} + +void VideoStreaming::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void VideoStreaming::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera_server.VideoStreaming) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.rtsp_uri_.ClearToEmpty(); + _impl_.has_rtsp_server_ = false; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* VideoStreaming::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // bool has_rtsp_server = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 8)) { + _impl_.has_rtsp_server_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + // string rtsp_uri = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 18)) { + auto str = _internal_mutable_rtsp_uri(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri")); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* VideoStreaming::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera_server.VideoStreaming) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // bool has_rtsp_server = 1; + if (this->_internal_has_rtsp_server() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 1, this->_internal_has_rtsp_server(), target); + } + + // string rtsp_uri = 2; + if (!this->_internal_rtsp_uri().empty()) { + const std::string& _s = this->_internal_rtsp_uri(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri"); + target = stream->WriteStringMaybeAliased(2, _s, target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.camera_server.VideoStreaming) + return target; +} + +::size_t VideoStreaming::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera_server.VideoStreaming) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string rtsp_uri = 2; + if (!this->_internal_rtsp_uri().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_rtsp_uri()); + } + + // bool has_rtsp_server = 1; + if (this->_internal_has_rtsp_server() != 0) { + total_size += 2; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData VideoStreaming::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + VideoStreaming::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*VideoStreaming::GetClassData() const { return &_class_data_; } + + +void VideoStreaming::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.camera_server.VideoStreaming) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_rtsp_uri().empty()) { + _this->_internal_set_rtsp_uri(from._internal_rtsp_uri()); + } + if (from._internal_has_rtsp_server() != 0) { + _this->_internal_set_has_rtsp_server(from._internal_has_rtsp_server()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void VideoStreaming::CopyFrom(const VideoStreaming& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera_server.VideoStreaming) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool VideoStreaming::IsInitialized() const { + return true; +} + +void VideoStreaming::InternalSwap(VideoStreaming* other) { + using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.rtsp_uri_, lhs_arena, + &other->_impl_.rtsp_uri_, rhs_arena); + + swap(_impl_.has_rtsp_server_, other->_impl_.has_rtsp_server_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata VideoStreaming::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[47]); } // =================================================================== @@ -9762,7 +10498,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[45]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[48]); } // =================================================================== @@ -10067,7 +10803,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[46]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[49]); } // =================================================================== @@ -10470,7 +11206,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[47]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[50]); } // =================================================================== @@ -10699,7 +11435,7 @@ void CameraServerResult::InternalSwap(CameraServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CameraServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[48]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[51]); } // =================================================================== @@ -11125,7 +11861,7 @@ void StorageInformation::InternalSwap(StorageInformation* other) { ::PROTOBUF_NAMESPACE_ID::Metadata StorageInformation::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[49]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[52]); } // =================================================================== @@ -11475,7 +12211,7 @@ void CaptureStatus::InternalSwap(CaptureStatus* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CaptureStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_getter, &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, - file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[50]); + file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto[53]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera_server @@ -11490,6 +12226,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInformationRespons Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInformationResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInformationResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetVideoStreamingRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetVideoStreamingRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetVideoStreamingResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetVideoStreamingResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::SetInProgressRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::SetInProgressRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::SetInProgressRequest >(arena); @@ -11662,6 +12406,10 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Information* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Information >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Information >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::VideoStreaming* +Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::VideoStreaming >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::VideoStreaming >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::camera_server::Position* Arena::CreateMaybeMessage< ::mavsdk::rpc::camera_server::Position >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::camera_server::Position >(arena); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index f3b7003115..b489a78bd6 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -158,6 +158,12 @@ extern SetInformationResponseDefaultTypeInternal _SetInformationResponse_default class SetModeResponse; struct SetModeResponseDefaultTypeInternal; extern SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; +class SetVideoStreamingRequest; +struct SetVideoStreamingRequestDefaultTypeInternal; +extern SetVideoStreamingRequestDefaultTypeInternal _SetVideoStreamingRequest_default_instance_; +class SetVideoStreamingResponse; +struct SetVideoStreamingResponseDefaultTypeInternal; +extern SetVideoStreamingResponseDefaultTypeInternal _SetVideoStreamingResponse_default_instance_; class StartVideoResponse; struct StartVideoResponseDefaultTypeInternal; extern StartVideoResponseDefaultTypeInternal _StartVideoResponse_default_instance_; @@ -209,6 +215,9 @@ extern SubscribeTakePhotoRequestDefaultTypeInternal _SubscribeTakePhotoRequest_d class TakePhotoResponse; struct TakePhotoResponseDefaultTypeInternal; extern TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; +class VideoStreaming; +struct VideoStreamingDefaultTypeInternal; +extern VideoStreamingDefaultTypeInternal _VideoStreaming_default_instance_; } // namespace camera_server } // namespace rpc } // namespace mavsdk @@ -282,6 +291,10 @@ ::mavsdk::rpc::camera_server::SetInformationResponse* Arena::CreateMaybeMessage< template <> ::mavsdk::rpc::camera_server::SetModeResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetModeResponse>(Arena*); template <> +::mavsdk::rpc::camera_server::SetVideoStreamingRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetVideoStreamingRequest>(Arena*); +template <> +::mavsdk::rpc::camera_server::SetVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SetVideoStreamingResponse>(Arena*); +template <> ::mavsdk::rpc::camera_server::StartVideoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoResponse>(Arena*); template <> ::mavsdk::rpc::camera_server::StartVideoStreamingResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::StartVideoStreamingResponse>(Arena*); @@ -315,6 +328,8 @@ template <> ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest>(Arena*); template <> ::mavsdk::rpc::camera_server::TakePhotoResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::TakePhotoResponse>(Arena*); +template <> +::mavsdk::rpc::camera_server::VideoStreaming* Arena::CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreaming>(Arena*); PROTOBUF_NAMESPACE_CLOSE namespace mavsdk { @@ -882,6 +897,326 @@ class SetInformationResponse final : friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; };// ------------------------------------------------------------------- +class SetVideoStreamingRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingRequest) */ { + public: + inline SetVideoStreamingRequest() : SetVideoStreamingRequest(nullptr) {} + ~SetVideoStreamingRequest() override; + template + explicit PROTOBUF_CONSTEXPR SetVideoStreamingRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetVideoStreamingRequest(const SetVideoStreamingRequest& from); + SetVideoStreamingRequest(SetVideoStreamingRequest&& from) noexcept + : SetVideoStreamingRequest() { + *this = ::std::move(from); + } + + inline SetVideoStreamingRequest& operator=(const SetVideoStreamingRequest& from) { + CopyFrom(from); + return *this; + } + inline SetVideoStreamingRequest& operator=(SetVideoStreamingRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SetVideoStreamingRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamingRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + friend void swap(SetVideoStreamingRequest& a, SetVideoStreamingRequest& b) { + a.Swap(&b); + } + inline void Swap(SetVideoStreamingRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetVideoStreamingRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetVideoStreamingRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetVideoStreamingRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const SetVideoStreamingRequest& from) { + SetVideoStreamingRequest::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetVideoStreamingRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SetVideoStreamingRequest"; + } + protected: + explicit SetVideoStreamingRequest(::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 { + kVideoStreamingFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; + bool has_video_streaming() const; + void clear_video_streaming() ; + const ::mavsdk::rpc::camera_server::VideoStreaming& video_streaming() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::VideoStreaming* release_video_streaming(); + ::mavsdk::rpc::camera_server::VideoStreaming* mutable_video_streaming(); + void set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* video_streaming); + private: + const ::mavsdk::rpc::camera_server::VideoStreaming& _internal_video_streaming() const; + ::mavsdk::rpc::camera_server::VideoStreaming* _internal_mutable_video_streaming(); + public: + void unsafe_arena_set_allocated_video_streaming( + ::mavsdk::rpc::camera_server::VideoStreaming* video_streaming); + ::mavsdk::rpc::camera_server::VideoStreaming* unsafe_arena_release_video_streaming(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::VideoStreaming* video_streaming_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SetVideoStreamingResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetVideoStreamingResponse) */ { + public: + inline SetVideoStreamingResponse() : SetVideoStreamingResponse(nullptr) {} + ~SetVideoStreamingResponse() override; + template + explicit PROTOBUF_CONSTEXPR SetVideoStreamingResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetVideoStreamingResponse(const SetVideoStreamingResponse& from); + SetVideoStreamingResponse(SetVideoStreamingResponse&& from) noexcept + : SetVideoStreamingResponse() { + *this = ::std::move(from); + } + + inline SetVideoStreamingResponse& operator=(const SetVideoStreamingResponse& from) { + CopyFrom(from); + return *this; + } + inline SetVideoStreamingResponse& operator=(SetVideoStreamingResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SetVideoStreamingResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetVideoStreamingResponse* internal_default_instance() { + return reinterpret_cast( + &_SetVideoStreamingResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + friend void swap(SetVideoStreamingResponse& a, SetVideoStreamingResponse& b) { + a.Swap(&b); + } + inline void Swap(SetVideoStreamingResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetVideoStreamingResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetVideoStreamingResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetVideoStreamingResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const SetVideoStreamingResponse& from) { + SetVideoStreamingResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetVideoStreamingResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.SetVideoStreamingResponse"; + } + protected: + explicit SetVideoStreamingResponse(::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 { + kCameraServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; + bool has_camera_server_result() const; + void clear_camera_server_result() ; + const ::mavsdk::rpc::camera_server::CameraServerResult& camera_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera_server::CameraServerResult* release_camera_server_result(); + ::mavsdk::rpc::camera_server::CameraServerResult* mutable_camera_server_result(); + void set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + private: + const ::mavsdk::rpc::camera_server::CameraServerResult& _internal_camera_server_result() const; + ::mavsdk::rpc::camera_server::CameraServerResult* _internal_mutable_camera_server_result(); + public: + void unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result); + ::mavsdk::rpc::camera_server::CameraServerResult* unsafe_arena_release_camera_server_result(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.SetVideoStreamingResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + class SetInProgressRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.SetInProgressRequest) */ { public: @@ -938,7 +1273,7 @@ class SetInProgressRequest final : &_SetInProgressRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 4; friend void swap(SetInProgressRequest& a, SetInProgressRequest& b) { a.Swap(&b); @@ -1093,7 +1428,7 @@ class SetInProgressResponse final : &_SetInProgressResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 5; friend void swap(SetInProgressResponse& a, SetInProgressResponse& b) { a.Swap(&b); @@ -1252,7 +1587,7 @@ class SubscribeTakePhotoRequest final : &_SubscribeTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 6; friend void swap(SubscribeTakePhotoRequest& a, SubscribeTakePhotoRequest& b) { a.Swap(&b); @@ -1377,7 +1712,7 @@ class TakePhotoResponse final : &_TakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 7; friend void swap(TakePhotoResponse& a, TakePhotoResponse& b) { a.Swap(&b); @@ -1532,7 +1867,7 @@ class RespondTakePhotoRequest final : &_RespondTakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 8; friend void swap(RespondTakePhotoRequest& a, RespondTakePhotoRequest& b) { a.Swap(&b); @@ -1704,7 +2039,7 @@ class RespondTakePhotoResponse final : &_RespondTakePhotoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 9; friend void swap(RespondTakePhotoResponse& a, RespondTakePhotoResponse& b) { a.Swap(&b); @@ -1863,7 +2198,7 @@ class SubscribeStartVideoRequest final : &_SubscribeStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 10; friend void swap(SubscribeStartVideoRequest& a, SubscribeStartVideoRequest& b) { a.Swap(&b); @@ -1988,7 +2323,7 @@ class StartVideoResponse final : &_StartVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 11; friend void swap(StartVideoResponse& a, StartVideoResponse& b) { a.Swap(&b); @@ -2143,7 +2478,7 @@ class RespondStartVideoRequest final : &_RespondStartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 12; friend void swap(RespondStartVideoRequest& a, RespondStartVideoRequest& b) { a.Swap(&b); @@ -2298,7 +2633,7 @@ class RespondStartVideoResponse final : &_RespondStartVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 13; friend void swap(RespondStartVideoResponse& a, RespondStartVideoResponse& b) { a.Swap(&b); @@ -2457,7 +2792,7 @@ class SubscribeStopVideoRequest final : &_SubscribeStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 14; friend void swap(SubscribeStopVideoRequest& a, SubscribeStopVideoRequest& b) { a.Swap(&b); @@ -2582,7 +2917,7 @@ class StopVideoResponse final : &_StopVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 15; friend void swap(StopVideoResponse& a, StopVideoResponse& b) { a.Swap(&b); @@ -2737,7 +3072,7 @@ class RespondStopVideoRequest final : &_RespondStopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 16; friend void swap(RespondStopVideoRequest& a, RespondStopVideoRequest& b) { a.Swap(&b); @@ -2892,7 +3227,7 @@ class RespondStopVideoResponse final : &_RespondStopVideoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 17; friend void swap(RespondStopVideoResponse& a, RespondStopVideoResponse& b) { a.Swap(&b); @@ -3051,7 +3386,7 @@ class SubscribeStartVideoStreamingRequest final : &_SubscribeStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 18; friend void swap(SubscribeStartVideoStreamingRequest& a, SubscribeStartVideoStreamingRequest& b) { a.Swap(&b); @@ -3176,7 +3511,7 @@ class StartVideoStreamingResponse final : &_StartVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 19; friend void swap(StartVideoStreamingResponse& a, StartVideoStreamingResponse& b) { a.Swap(&b); @@ -3331,7 +3666,7 @@ class RespondStartVideoStreamingRequest final : &_RespondStartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 20; friend void swap(RespondStartVideoStreamingRequest& a, RespondStartVideoStreamingRequest& b) { a.Swap(&b); @@ -3486,7 +3821,7 @@ class RespondStartVideoStreamingResponse final : &_RespondStartVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 21; friend void swap(RespondStartVideoStreamingResponse& a, RespondStartVideoStreamingResponse& b) { a.Swap(&b); @@ -3645,7 +3980,7 @@ class SubscribeStopVideoStreamingRequest final : &_SubscribeStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 22; friend void swap(SubscribeStopVideoStreamingRequest& a, SubscribeStopVideoStreamingRequest& b) { a.Swap(&b); @@ -3770,7 +4105,7 @@ class StopVideoStreamingResponse final : &_StopVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 23; friend void swap(StopVideoStreamingResponse& a, StopVideoStreamingResponse& b) { a.Swap(&b); @@ -3925,7 +4260,7 @@ class RespondStopVideoStreamingRequest final : &_RespondStopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 24; friend void swap(RespondStopVideoStreamingRequest& a, RespondStopVideoStreamingRequest& b) { a.Swap(&b); @@ -4080,7 +4415,7 @@ class RespondStopVideoStreamingResponse final : &_RespondStopVideoStreamingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 25; friend void swap(RespondStopVideoStreamingResponse& a, RespondStopVideoStreamingResponse& b) { a.Swap(&b); @@ -4239,7 +4574,7 @@ class SubscribeSetModeRequest final : &_SubscribeSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 26; friend void swap(SubscribeSetModeRequest& a, SubscribeSetModeRequest& b) { a.Swap(&b); @@ -4364,7 +4699,7 @@ class SetModeResponse final : &_SetModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 25; + 27; friend void swap(SetModeResponse& a, SetModeResponse& b) { a.Swap(&b); @@ -4519,7 +4854,7 @@ class RespondSetModeRequest final : &_RespondSetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 28; friend void swap(RespondSetModeRequest& a, RespondSetModeRequest& b) { a.Swap(&b); @@ -4674,7 +5009,7 @@ class RespondSetModeResponse final : &_RespondSetModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 27; + 29; friend void swap(RespondSetModeResponse& a, RespondSetModeResponse& b) { a.Swap(&b); @@ -4833,7 +5168,7 @@ class SubscribeStorageInformationRequest final : &_SubscribeStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 30; friend void swap(SubscribeStorageInformationRequest& a, SubscribeStorageInformationRequest& b) { a.Swap(&b); @@ -4958,7 +5293,7 @@ class StorageInformationResponse final : &_StorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 29; + 31; friend void swap(StorageInformationResponse& a, StorageInformationResponse& b) { a.Swap(&b); @@ -5113,7 +5448,7 @@ class RespondStorageInformationRequest final : &_RespondStorageInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 32; friend void swap(RespondStorageInformationRequest& a, RespondStorageInformationRequest& b) { a.Swap(&b); @@ -5285,7 +5620,7 @@ class RespondStorageInformationResponse final : &_RespondStorageInformationResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 31; + 33; friend void swap(RespondStorageInformationResponse& a, RespondStorageInformationResponse& b) { a.Swap(&b); @@ -5444,7 +5779,7 @@ class SubscribeCaptureStatusRequest final : &_SubscribeCaptureStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 34; friend void swap(SubscribeCaptureStatusRequest& a, SubscribeCaptureStatusRequest& b) { a.Swap(&b); @@ -5569,7 +5904,7 @@ class CaptureStatusResponse final : &_CaptureStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 33; + 35; friend void swap(CaptureStatusResponse& a, CaptureStatusResponse& b) { a.Swap(&b); @@ -5724,7 +6059,7 @@ class RespondCaptureStatusRequest final : &_RespondCaptureStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 34; + 36; friend void swap(RespondCaptureStatusRequest& a, RespondCaptureStatusRequest& b) { a.Swap(&b); @@ -5896,7 +6231,7 @@ class RespondCaptureStatusResponse final : &_RespondCaptureStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 35; + 37; friend void swap(RespondCaptureStatusResponse& a, RespondCaptureStatusResponse& b) { a.Swap(&b); @@ -6055,7 +6390,7 @@ class SubscribeFormatStorageRequest final : &_SubscribeFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 36; + 38; friend void swap(SubscribeFormatStorageRequest& a, SubscribeFormatStorageRequest& b) { a.Swap(&b); @@ -6180,7 +6515,7 @@ class FormatStorageResponse final : &_FormatStorageResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 37; + 39; friend void swap(FormatStorageResponse& a, FormatStorageResponse& b) { a.Swap(&b); @@ -6335,7 +6670,7 @@ class RespondFormatStorageRequest final : &_RespondFormatStorageRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 38; + 40; friend void swap(RespondFormatStorageRequest& a, RespondFormatStorageRequest& b) { a.Swap(&b); @@ -6490,7 +6825,7 @@ class RespondFormatStorageResponse final : &_RespondFormatStorageResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 39; + 41; friend void swap(RespondFormatStorageResponse& a, RespondFormatStorageResponse& b) { a.Swap(&b); @@ -6649,7 +6984,7 @@ class SubscribeResetSettingsRequest final : &_SubscribeResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 40; + 42; friend void swap(SubscribeResetSettingsRequest& a, SubscribeResetSettingsRequest& b) { a.Swap(&b); @@ -6774,7 +7109,7 @@ class ResetSettingsResponse final : &_ResetSettingsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 41; + 43; friend void swap(ResetSettingsResponse& a, ResetSettingsResponse& b) { a.Swap(&b); @@ -6929,7 +7264,7 @@ class RespondResetSettingsRequest final : &_RespondResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 44; friend void swap(RespondResetSettingsRequest& a, RespondResetSettingsRequest& b) { a.Swap(&b); @@ -7084,7 +7419,7 @@ class RespondResetSettingsResponse final : &_RespondResetSettingsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 43; + 45; friend void swap(RespondResetSettingsResponse& a, RespondResetSettingsResponse& b) { a.Swap(&b); @@ -7244,7 +7579,7 @@ class Information final : &_Information_default_instance_); } static constexpr int kIndexInFileMessages = - 44; + 46; friend void swap(Information& a, Information& b) { a.Swap(&b); @@ -7413,72 +7748,258 @@ class Information final : float focal_length_mm() const; void set_focal_length_mm(float value); - private: - float _internal_focal_length_mm() const; - void _internal_set_focal_length_mm(float value); + private: + float _internal_focal_length_mm() const; + void _internal_set_focal_length_mm(float value); + + public: + // float horizontal_sensor_size_mm = 5; + void clear_horizontal_sensor_size_mm() ; + float horizontal_sensor_size_mm() const; + void set_horizontal_sensor_size_mm(float value); + + private: + float _internal_horizontal_sensor_size_mm() const; + void _internal_set_horizontal_sensor_size_mm(float value); + + public: + // float vertical_sensor_size_mm = 6; + void clear_vertical_sensor_size_mm() ; + float vertical_sensor_size_mm() const; + void set_vertical_sensor_size_mm(float value); + + private: + float _internal_vertical_sensor_size_mm() const; + void _internal_set_vertical_sensor_size_mm(float value); + + public: + // uint32 horizontal_resolution_px = 7; + void clear_horizontal_resolution_px() ; + ::uint32_t horizontal_resolution_px() const; + void set_horizontal_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_horizontal_resolution_px() const; + void _internal_set_horizontal_resolution_px(::uint32_t value); + + public: + // uint32 vertical_resolution_px = 8; + void clear_vertical_resolution_px() ; + ::uint32_t vertical_resolution_px() const; + void set_vertical_resolution_px(::uint32_t value); + + private: + ::uint32_t _internal_vertical_resolution_px() const; + void _internal_set_vertical_resolution_px(::uint32_t value); + + public: + // uint32 lens_id = 9; + void clear_lens_id() ; + ::uint32_t lens_id() const; + void set_lens_id(::uint32_t value); + + private: + ::uint32_t _internal_lens_id() const; + void _internal_set_lens_id(::uint32_t value); + + public: + // uint32 definition_file_version = 10; + void clear_definition_file_version() ; + ::uint32_t definition_file_version() const; + void set_definition_file_version(::uint32_t value); + + private: + ::uint32_t _internal_definition_file_version() const; + void _internal_set_definition_file_version(::uint32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; + float focal_length_mm_; + float horizontal_sensor_size_mm_; + float vertical_sensor_size_mm_; + ::uint32_t horizontal_resolution_px_; + ::uint32_t vertical_resolution_px_; + ::uint32_t lens_id_; + ::uint32_t definition_file_version_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class VideoStreaming final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera_server.VideoStreaming) */ { + public: + inline VideoStreaming() : VideoStreaming(nullptr) {} + ~VideoStreaming() override; + template + explicit PROTOBUF_CONSTEXPR VideoStreaming(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + VideoStreaming(const VideoStreaming& from); + VideoStreaming(VideoStreaming&& from) noexcept + : VideoStreaming() { + *this = ::std::move(from); + } + + inline VideoStreaming& operator=(const VideoStreaming& from) { + CopyFrom(from); + return *this; + } + inline VideoStreaming& operator=(VideoStreaming&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 VideoStreaming& default_instance() { + return *internal_default_instance(); + } + static inline const VideoStreaming* internal_default_instance() { + return reinterpret_cast( + &_VideoStreaming_default_instance_); + } + static constexpr int kIndexInFileMessages = + 47; + + friend void swap(VideoStreaming& a, VideoStreaming& b) { + a.Swap(&b); + } + inline void Swap(VideoStreaming* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(VideoStreaming* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + VideoStreaming* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const VideoStreaming& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const VideoStreaming& from) { + VideoStreaming::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); public: - // float horizontal_sensor_size_mm = 5; - void clear_horizontal_sensor_size_mm() ; - float horizontal_sensor_size_mm() const; - void set_horizontal_sensor_size_mm(float value); + 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; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } private: - float _internal_horizontal_sensor_size_mm() const; - void _internal_set_horizontal_sensor_size_mm(float value); + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(VideoStreaming* other); + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.camera_server.VideoStreaming"; + } + protected: + explicit VideoStreaming(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: - // float vertical_sensor_size_mm = 6; - void clear_vertical_sensor_size_mm() ; - float vertical_sensor_size_mm() const; - void set_vertical_sensor_size_mm(float value); - private: - float _internal_vertical_sensor_size_mm() const; - void _internal_set_vertical_sensor_size_mm(float value); + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; - public: - // uint32 horizontal_resolution_px = 7; - void clear_horizontal_resolution_px() ; - ::uint32_t horizontal_resolution_px() const; - void set_horizontal_resolution_px(::uint32_t value); + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; - private: - ::uint32_t _internal_horizontal_resolution_px() const; - void _internal_set_horizontal_resolution_px(::uint32_t value); + // nested types ---------------------------------------------------- - public: - // uint32 vertical_resolution_px = 8; - void clear_vertical_resolution_px() ; - ::uint32_t vertical_resolution_px() const; - void set_vertical_resolution_px(::uint32_t value); + // accessors ------------------------------------------------------- + + enum : int { + kRtspUriFieldNumber = 2, + kHasRtspServerFieldNumber = 1, + }; + // string rtsp_uri = 2; + void clear_rtsp_uri() ; + const std::string& rtsp_uri() const; - private: - ::uint32_t _internal_vertical_resolution_px() const; - void _internal_set_vertical_resolution_px(::uint32_t value); - public: - // uint32 lens_id = 9; - void clear_lens_id() ; - ::uint32_t lens_id() const; - void set_lens_id(::uint32_t value); + + + template + void set_rtsp_uri(Arg_&& arg, Args_... args); + std::string* mutable_rtsp_uri(); + PROTOBUF_NODISCARD std::string* release_rtsp_uri(); + void set_allocated_rtsp_uri(std::string* ptr); private: - ::uint32_t _internal_lens_id() const; - void _internal_set_lens_id(::uint32_t value); + const std::string& _internal_rtsp_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_rtsp_uri( + const std::string& value); + std::string* _internal_mutable_rtsp_uri(); public: - // uint32 definition_file_version = 10; - void clear_definition_file_version() ; - ::uint32_t definition_file_version() const; - void set_definition_file_version(::uint32_t value); + // bool has_rtsp_server = 1; + void clear_has_rtsp_server() ; + bool has_rtsp_server() const; + void set_has_rtsp_server(bool value); private: - ::uint32_t _internal_definition_file_version() const; - void _internal_set_definition_file_version(::uint32_t value); + bool _internal_has_rtsp_server() const; + void _internal_set_has_rtsp_server(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.VideoStreaming) private: class _Internal; @@ -7486,17 +8007,8 @@ class Information final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; - float focal_length_mm_; - float horizontal_sensor_size_mm_; - float vertical_sensor_size_mm_; - ::uint32_t horizontal_resolution_px_; - ::uint32_t vertical_resolution_px_; - ::uint32_t lens_id_; - ::uint32_t definition_file_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr rtsp_uri_; + bool has_rtsp_server_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; union { Impl_ _impl_; }; @@ -7559,7 +8071,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 45; + 48; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -7750,7 +8262,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 49; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -7941,7 +8453,7 @@ class CaptureInfo final : &_CaptureInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 47; + 50; friend void swap(CaptureInfo& a, CaptureInfo& b) { a.Swap(&b); @@ -8175,7 +8687,7 @@ class CameraServerResult final : &_CameraServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 51; friend void swap(CameraServerResult& a, CameraServerResult& b) { a.Swap(&b); @@ -8379,7 +8891,7 @@ class StorageInformation final : &_StorageInformation_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 52; friend void swap(StorageInformation& a, StorageInformation& b) { a.Swap(&b); @@ -8664,7 +9176,7 @@ class CaptureStatus final : &_CaptureStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 53; friend void swap(CaptureStatus& a, CaptureStatus& b) { a.Swap(&b); @@ -9061,6 +9573,188 @@ inline void SetInformationResponse::set_allocated_camera_server_result(::mavsdk: // ------------------------------------------------------------------- +// SetVideoStreamingRequest + +// .mavsdk.rpc.camera_server.VideoStreaming video_streaming = 1; +inline bool SetVideoStreamingRequest::has_video_streaming() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.video_streaming_ != nullptr); + return value; +} +inline void SetVideoStreamingRequest::clear_video_streaming() { + if (_impl_.video_streaming_ != nullptr) _impl_.video_streaming_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::_internal_video_streaming() const { + const ::mavsdk::rpc::camera_server::VideoStreaming* p = _impl_.video_streaming_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_VideoStreaming_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::VideoStreaming& SetVideoStreamingRequest::video_streaming() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) + return _internal_video_streaming(); +} +inline void SetVideoStreamingRequest::unsafe_arena_set_allocated_video_streaming( + ::mavsdk::rpc::camera_server::VideoStreaming* video_streaming) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.video_streaming_); + } + _impl_.video_streaming_ = video_streaming; + if (video_streaming) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) +} +inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::release_video_streaming() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::VideoStreaming* temp = _impl_.video_streaming_; + _impl_.video_streaming_ = 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::camera_server::VideoStreaming* SetVideoStreamingRequest::unsafe_arena_release_video_streaming() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::VideoStreaming* temp = _impl_.video_streaming_; + _impl_.video_streaming_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::_internal_mutable_video_streaming() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.video_streaming_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::VideoStreaming>(GetArenaForAllocation()); + _impl_.video_streaming_ = p; + } + return _impl_.video_streaming_; +} +inline ::mavsdk::rpc::camera_server::VideoStreaming* SetVideoStreamingRequest::mutable_video_streaming() { + ::mavsdk::rpc::camera_server::VideoStreaming* _msg = _internal_mutable_video_streaming(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) + return _msg; +} +inline void SetVideoStreamingRequest::set_allocated_video_streaming(::mavsdk::rpc::camera_server::VideoStreaming* video_streaming) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.video_streaming_; + } + if (video_streaming) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(video_streaming); + if (message_arena != submessage_arena) { + video_streaming = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, video_streaming, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.video_streaming_ = video_streaming; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingRequest.video_streaming) +} + +// ------------------------------------------------------------------- + +// SetVideoStreamingResponse + +// .mavsdk.rpc.camera_server.CameraServerResult camera_server_result = 1; +inline bool SetVideoStreamingResponse::has_camera_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.camera_server_result_ != nullptr); + return value; +} +inline void SetVideoStreamingResponse::clear_camera_server_result() { + if (_impl_.camera_server_result_ != nullptr) _impl_.camera_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamingResponse::_internal_camera_server_result() const { + const ::mavsdk::rpc::camera_server::CameraServerResult* p = _impl_.camera_server_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::camera_server::_CameraServerResult_default_instance_); +} +inline const ::mavsdk::rpc::camera_server::CameraServerResult& SetVideoStreamingResponse::camera_server_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + return _internal_camera_server_result(); +} +inline void SetVideoStreamingResponse::unsafe_arena_set_allocated_camera_server_result( + ::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.camera_server_result_); + } + _impl_.camera_server_result_ = camera_server_result; + if (camera_server_result) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::release_camera_server_result() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_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::camera_server::CameraServerResult* SetVideoStreamingResponse::unsafe_arena_release_camera_server_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::camera_server::CameraServerResult* temp = _impl_.camera_server_result_; + _impl_.camera_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::_internal_mutable_camera_server_result() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.camera_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::camera_server::CameraServerResult>(GetArenaForAllocation()); + _impl_.camera_server_result_ = p; + } + return _impl_.camera_server_result_; +} +inline ::mavsdk::rpc::camera_server::CameraServerResult* SetVideoStreamingResponse::mutable_camera_server_result() { + ::mavsdk::rpc::camera_server::CameraServerResult* _msg = _internal_mutable_camera_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) + return _msg; +} +inline void SetVideoStreamingResponse::set_allocated_camera_server_result(::mavsdk::rpc::camera_server::CameraServerResult* camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.camera_server_result_; + } + if (camera_server_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(camera_server_result); + if (message_arena != submessage_arena) { + camera_server_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, camera_server_result, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.camera_server_result_ = camera_server_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.SetVideoStreamingResponse.camera_server_result) +} + +// ------------------------------------------------------------------- + // SetInProgressRequest // bool in_progress = 1; @@ -11199,6 +11893,77 @@ inline void Information::set_allocated_definition_file_uri(std::string* value) { // ------------------------------------------------------------------- +// VideoStreaming + +// bool has_rtsp_server = 1; +inline void VideoStreaming::clear_has_rtsp_server() { + _impl_.has_rtsp_server_ = false; +} +inline bool VideoStreaming::has_rtsp_server() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreaming.has_rtsp_server) + return _internal_has_rtsp_server(); +} +inline void VideoStreaming::set_has_rtsp_server(bool value) { + _internal_set_has_rtsp_server(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreaming.has_rtsp_server) +} +inline bool VideoStreaming::_internal_has_rtsp_server() const { + return _impl_.has_rtsp_server_; +} +inline void VideoStreaming::_internal_set_has_rtsp_server(bool value) { + ; + _impl_.has_rtsp_server_ = value; +} + +// string rtsp_uri = 2; +inline void VideoStreaming::clear_rtsp_uri() { + _impl_.rtsp_uri_.ClearToEmpty(); +} +inline const std::string& VideoStreaming::rtsp_uri() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) + return _internal_rtsp_uri(); +} +template +inline PROTOBUF_ALWAYS_INLINE void VideoStreaming::set_rtsp_uri(Arg_&& arg, + Args_... args) { + ; + _impl_.rtsp_uri_.Set(static_cast(arg), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) +} +inline std::string* VideoStreaming::mutable_rtsp_uri() { + std::string* _s = _internal_mutable_rtsp_uri(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) + return _s; +} +inline const std::string& VideoStreaming::_internal_rtsp_uri() const { + return _impl_.rtsp_uri_.Get(); +} +inline void VideoStreaming::_internal_set_rtsp_uri(const std::string& value) { + ; + + + _impl_.rtsp_uri_.Set(value, GetArenaForAllocation()); +} +inline std::string* VideoStreaming::_internal_mutable_rtsp_uri() { + ; + return _impl_.rtsp_uri_.Mutable( GetArenaForAllocation()); +} +inline std::string* VideoStreaming::release_rtsp_uri() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) + return _impl_.rtsp_uri_.Release(); +} +inline void VideoStreaming::set_allocated_rtsp_uri(std::string* value) { + _impl_.rtsp_uri_.SetAllocated(value, GetArenaForAllocation()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.rtsp_uri_.IsDefault()) { + _impl_.rtsp_uri_.Set("", GetArenaForAllocation()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.VideoStreaming.rtsp_uri) +} + +// ------------------------------------------------------------------- + // Position // double latitude_deg = 1; diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 22a56f9c64..8e927bf2f1 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -172,6 +172,30 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return obj; } + static std::unique_ptr + translateToRpcVideoStreaming(const mavsdk::CameraServer::VideoStreaming& video_streaming) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_has_rtsp_server(video_streaming.has_rtsp_server); + + rpc_obj->set_rtsp_uri(video_streaming.rtsp_uri); + + return rpc_obj; + } + + static mavsdk::CameraServer::VideoStreaming + translateFromRpcVideoStreaming(const rpc::camera_server::VideoStreaming& video_streaming) + { + mavsdk::CameraServer::VideoStreaming obj; + + obj.has_rtsp_server = video_streaming.has_rtsp_server(); + + obj.rtsp_uri = video_streaming.rtsp_uri(); + + return obj; + } + static std::unique_ptr translateToRpcPosition(const mavsdk::CameraServer::Position& position) { @@ -606,6 +630,37 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer return grpc::Status::OK; } + grpc::Status SetVideoStreaming( + grpc::ServerContext* /* context */, + const rpc::camera_server::SetVideoStreamingRequest* request, + rpc::camera_server::SetVideoStreamingResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::CameraServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetVideoStreaming sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_video_streaming( + translateFromRpcVideoStreaming(request->video_streaming())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status SetInProgress( grpc::ServerContext* /* context */, const rpc::camera_server::SetInProgressRequest* request, diff --git a/third_party/mavlink/CMakeLists.txt b/third_party/mavlink/CMakeLists.txt index 6508bf01a7..6278270c5f 100644 --- a/third_party/mavlink/CMakeLists.txt +++ b/third_party/mavlink/CMakeLists.txt @@ -24,7 +24,7 @@ else() ExternalProject_add( mavlink GIT_REPOSITORY https://github.com/mavlink/mavlink - GIT_TAG 18955a04c7c7467e00ea42b704addb4a9c12b53a + GIT_TAG 81524c2b34aa08768f13091b1d94c421e64f96c3 PREFIX mavlink PATCH_COMMAND git checkout . && git apply ${PROJECT_SOURCE_DIR}/mavlink.patch CMAKE_ARGS "${CMAKE_ARGS}" From d2630219d2bd9e665b1036da57184f8aa98c2049 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 06:25:51 +1300 Subject: [PATCH 11/25] core: don't complain about ping Signed-off-by: Julian Oes --- src/mavsdk/core/ping.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mavsdk/core/ping.cpp b/src/mavsdk/core/ping.cpp index ad49a6b7c2..b9b234c95d 100644 --- a/src/mavsdk/core/ping.cpp +++ b/src/mavsdk/core/ping.cpp @@ -60,7 +60,7 @@ void Ping::process_ping(const mavlink_message_t& message) } else { // Answer from ping request. if (ping.seq != _ping_sequence) { - LogWarn() << "Ignoring unknown ping sequence"; + // Ignoring unknown ping sequence. return; } From 5eceed795f28dba058600f949ebaa0a0b6761ac1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 08:28:07 +1300 Subject: [PATCH 12/25] camera_server: remove confusing duplicate logic I don't understand what this should be doing. I don't think it's right. Signed-off-by: Julian Oes --- src/mavsdk/plugins/camera_server/camera_server_impl.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 2a9bcc1546..93c6c5366f 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -1235,13 +1235,6 @@ CameraServerImpl::process_image_start_capture(const MavlinkCommandReceiver::Comm // single image capture if (total_images == 1) { - if (seq_number <= _image_capture_count) { - LogDebug() << "received duplicate single image capture request"; - // We know we already captured this request, so we can just ack it. - return _server_component_impl->make_command_ack_message( - command, MAV_RESULT::MAV_RESULT_ACCEPTED); - } - // MAV_RESULT_ACCEPTED must be sent before CAMERA_IMAGE_CAPTURED auto command_ack = _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_IN_PROGRESS); From eebc377bbe207d5d51f8a9f9834d61a68a4c89b4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 10:56:22 +1300 Subject: [PATCH 13/25] camera_server: remove sleeps (and some docstrings) The sleeps were required because forwarding is broken in PX4. This will hopefully be fixed with PX4 v1.14.1. Signed-off-by: Julian Oes --- .../camera_server/camera_server_impl.cpp | 19 +------------------ 1 file changed, 1 insertion(+), 18 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 93c6c5366f..853242ea31 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -1,8 +1,6 @@ #include "camera_server_impl.h" #include "callback_list.tpp" -#include // FIXME: remove me - namespace mavsdk { template class CallbackList; @@ -632,6 +630,7 @@ CameraServerImpl::subscribe_capture_status(const CameraServer::CaptureStatusCall { return _capture_status_callbacks.subscribe(callback); } + void CameraServerImpl::unsubscribe_capture_status(CameraServer::CaptureStatusHandle handle) { _capture_status_callbacks.unsubscribe(handle); @@ -797,13 +796,6 @@ CameraServerImpl::respond_reset_settings(CameraServer::CameraFeedback reset_sett return CameraServer::Result::Success; } -/** - * Starts capturing images with the given interval. - * @param [in] interval_s The interval between captures in seconds. - * @param [in] count The number of images to capture or 0 for "forever". - * @param [in] index The index/sequence number pass to the user callback (always - * @c INT32_MIN). - */ void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t count, int32_t index) { // If count == 0, it means capture "forever" until a stop command is received. @@ -829,9 +821,6 @@ void CameraServerImpl::start_image_capture_interval(float interval_s, int32_t co _image_capture_timer_interval_s = interval_s; } -/** - * Stops any pending image capture interval timer. - */ void CameraServerImpl::stop_image_capture_interval() { if (_image_capture_timer_cookie) { @@ -866,9 +855,6 @@ std::optional CameraServerImpl::process_camera_informatio _server_component_impl->send_command_ack(command_ack); LogDebug() << "sent info ack"; - // FIXME: why is this needed to prevent dropping messages? - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - // It is safe to ignore the return value of parse_version_string() here // since the string was already validated in set_information(). uint32_t firmware_version; @@ -936,9 +922,6 @@ std::optional CameraServerImpl::process_camera_settings_r _server_component_impl->send_command_ack(command_ack); LogDebug() << "sent settings ack"; - // FIXME: why is this needed to prevent dropping messages? - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - // unsupported const auto mode_id = CAMERA_MODE::CAMERA_MODE_IMAGE; const float zoom_level = 0; From e3f23f08678dcca7aefe2cf7de702cd66d7f108f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 10:58:52 +1300 Subject: [PATCH 14/25] camera_server: set capture video flag Signed-off-by: Julian Oes --- src/mavsdk/plugins/camera_server/camera_server_impl.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 853242ea31..ee39755135 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -867,6 +867,10 @@ std::optional CameraServerImpl::process_camera_informatio capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_IMAGE; } + if (!_start_video_callbacks.empty()) { + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; + } + if (_is_video_streaming_set) { capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } From 14c60fc0ec5faf6c9f372902ad14654cfb2d45d9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 12:03:08 +1300 Subject: [PATCH 15/25] camera_server: fix capture status And keep track of the state properly. Signed-off-by: Julian Oes --- .../camera_server/camera_server_impl.cpp | 84 +++++++------------ .../camera_server/camera_server_impl.h | 4 + 2 files changed, 34 insertions(+), 54 deletions(-) diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index ee39755135..4fd582232b 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -666,51 +666,9 @@ CameraServer::Result CameraServerImpl::respond_capture_status( } } - uint8_t image_status{}; - if (capture_status.image_status == - CameraServer::CaptureStatus::ImageStatus::CaptureInProgress || - capture_status.image_status == - CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) { - image_status |= StatusFlags::IN_PROGRESS; - } + _capture_status = capture_status; - if (capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle || - capture_status.image_status == - CameraServer::CaptureStatus::ImageStatus::IntervalInProgress || - _is_image_capture_interval_set) { - image_status |= StatusFlags::INTERVAL_SET; - } - - uint8_t video_status = 0; - if (capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) { - video_status = 0; - } else if ( - capture_status.video_status == - CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) { - video_status = 1; - } - const uint32_t recording_time_ms = - static_cast(static_cast(capture_status.recording_time_s) * 1e3); - const float available_capacity = capture_status.available_capacity_mib; - - // FIXME for now the image catpure interval is the interval state of the camera server - // so the capture_status.image_interval_s is useless for now - _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { - mavlink_message_t message{}; - mavlink_msg_camera_capture_status_pack_chan( - mavlink_address.system_id, - mavlink_address.component_id, - channel, - &message, - static_cast(_server_component_impl->get_time().elapsed_s() * 1e3), - image_status, - video_status, - _image_capture_timer_interval_s, - recording_time_ms, - available_capacity, - _image_capture_count); - return message; - }); + send_capture_status(); return CameraServer::Result::Success; } @@ -1070,20 +1028,41 @@ std::optional CameraServerImpl::process_camera_capture_st // may not need param for now ,just use zero _capture_status_callbacks(0); - uint8_t image_status{}; + send_capture_status(); - if (_is_image_capture_in_progress) { + // ack was already sent + return std::nullopt; +} + +void CameraServerImpl::send_capture_status() +{ + uint8_t image_status{}; + if (_capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::CaptureInProgress || + _capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::IntervalInProgress) { image_status |= StatusFlags::IN_PROGRESS; } - if (_is_image_capture_interval_set) { + if (_capture_status.image_status == CameraServer::CaptureStatus::ImageStatus::IntervalIdle || + _capture_status.image_status == + CameraServer::CaptureStatus::ImageStatus::IntervalInProgress || + _is_image_capture_interval_set) { image_status |= StatusFlags::INTERVAL_SET; } - // unsupported - const uint8_t video_status = 0; - const uint32_t recording_time_ms = 0; - const float available_capacity = 0; + uint8_t video_status = 0; + if (_capture_status.video_status == CameraServer::CaptureStatus::VideoStatus::Idle) { + video_status = 0; + } else if ( + _capture_status.video_status == + CameraServer::CaptureStatus::VideoStatus::CaptureInProgress) { + video_status = 1; + } + + const uint32_t recording_time_ms = + static_cast(static_cast(_capture_status.recording_time_s) * 1e3); + const float available_capacity = _capture_status.available_capacity_mib; _server_component_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message{}; @@ -1101,9 +1080,6 @@ std::optional CameraServerImpl::process_camera_capture_st _image_capture_count); return message; }); - - // ack was already sent - return std::nullopt; } std::optional diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index a88f728790..90dc8698a0 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -93,6 +93,8 @@ class CameraServerImpl : public ServerPluginImplBase { bool _is_video_streaming_set{}; CameraServer::VideoStreaming _video_streaming{}; + CameraServer::CaptureStatus _capture_status{}; + // CAMERA_CAPTURE_STATUS fields // TODO: how do we keep this info in sync between plugin instances? bool _is_image_capture_in_progress{}; @@ -168,6 +170,8 @@ class CameraServerImpl : public ServerPluginImplBase { process_video_stream_information_request(const MavlinkCommandReceiver::CommandLong& command); std::optional process_video_stream_status_request(const MavlinkCommandReceiver::CommandLong& command); + + void send_capture_status(); }; } // namespace mavsdk From c465bc686ab7d4e7dd718efdcd220aad5b6a759a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 12:03:33 +1300 Subject: [PATCH 16/25] camera_server: don't forget to send mode flag Signed-off-by: Julian Oes --- src/mavsdk/plugins/camera_server/camera_server_impl.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 4fd582232b..a65fd5c4e4 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -829,6 +829,10 @@ std::optional CameraServerImpl::process_camera_informatio capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_CAPTURE_VIDEO; } + if (!_set_mode_callbacks.empty()) { + capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_MODES; + } + if (_is_video_streaming_set) { capability_flags |= CAMERA_CAP_FLAGS::CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } From c3067b7f752826501602a591b2699c14a68c33d4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 13:45:46 +1300 Subject: [PATCH 17/25] core: allow change param unsubscriptions Signed-off-by: Julian Oes --- .../core/mavlink_parameter_subscription.cpp | 16 +++++++++++++++- src/mavsdk/core/mavlink_parameter_subscription.h | 4 +++- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/src/mavsdk/core/mavlink_parameter_subscription.cpp b/src/mavsdk/core/mavlink_parameter_subscription.cpp index e1d901e869..d59a9039d7 100644 --- a/src/mavsdk/core/mavlink_parameter_subscription.cpp +++ b/src/mavsdk/core/mavlink_parameter_subscription.cpp @@ -79,4 +79,18 @@ void MavlinkParameterSubscription::find_and_call_subscriptions_value_changed( } } -} // namespace mavsdk \ No newline at end of file +void MavlinkParameterSubscription::unsubscribe_all_params_changed(const void* cookie) +{ + std::lock_guard lock(_param_changed_subscriptions_mutex); + + for (auto it = _param_changed_subscriptions.begin(); it != _param_changed_subscriptions.end(); + /* it++ */) { + if (it->cookie == cookie) { + it = _param_changed_subscriptions.erase(it); + } else { + it++; + } + } +} + +} // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_parameter_subscription.h b/src/mavsdk/core/mavlink_parameter_subscription.h index 8447fb09cb..ddd7ce4605 100644 --- a/src/mavsdk/core/mavlink_parameter_subscription.h +++ b/src/mavsdk/core/mavlink_parameter_subscription.h @@ -35,6 +35,8 @@ class MavlinkParameterSubscription { void subscribe_param_custom_changed( const std::string& name, const ParamCustomChangedCallback& callback, const void* cookie); + void unsubscribe_all_params_changed(const void* cookie); + protected: /** * Find all the subscriptions for the given @param param_name, @@ -61,4 +63,4 @@ class MavlinkParameterSubscription { std::list _param_changed_subscriptions{}; }; -} // namespace mavsdk \ No newline at end of file +} // namespace mavsdk From 01ce134c7cff79ca8439e6ce1a25d66f90366e49 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Nov 2023 13:46:08 +1300 Subject: [PATCH 18/25] param_server: add param changed subscriptions This enables servers to be notified when a param changes. Signed-off-by: Julian Oes --- .../plugins/param_server/param_server.h | 62 + .../plugins/param_server/param_server.cpp | 33 + .../param_server/param_server_impl.cpp | 61 +- .../plugins/param_server/param_server_impl.h | 16 + .../param_server/param_server.grpc.pb.cc | 105 ++ .../param_server/param_server.grpc.pb.h | 485 ++++- .../generated/param_server/param_server.pb.cc | 1256 +++++++++++-- .../generated/param_server/param_server.pb.h | 1649 ++++++++++++++--- .../param_server/param_server_service_impl.h | 126 ++ 9 files changed, 3382 insertions(+), 411 deletions(-) diff --git a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h index 7fe235cb03..e1ad16894a 100644 --- a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h +++ b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h @@ -239,6 +239,68 @@ class ParamServer : public ServerPluginBase { */ ParamServer::AllParams retrieve_all_params() const; + /** + * @brief Callback type for subscribe_changed_param_int. + */ + using ChangedParamIntCallback = std::function; + + /** + * @brief Handle type for subscribe_changed_param_int. + */ + using ChangedParamIntHandle = Handle; + + /** + * @brief Subscribe to changed int param. + */ + ChangedParamIntHandle subscribe_changed_param_int(const ChangedParamIntCallback& callback); + + /** + * @brief Unsubscribe from subscribe_changed_param_int + */ + void unsubscribe_changed_param_int(ChangedParamIntHandle handle); + + /** + * @brief Callback type for subscribe_changed_param_float. + */ + using ChangedParamFloatCallback = std::function; + + /** + * @brief Handle type for subscribe_changed_param_float. + */ + using ChangedParamFloatHandle = Handle; + + /** + * @brief Subscribe to changed float param. + */ + ChangedParamFloatHandle + subscribe_changed_param_float(const ChangedParamFloatCallback& callback); + + /** + * @brief Unsubscribe from subscribe_changed_param_float + */ + void unsubscribe_changed_param_float(ChangedParamFloatHandle handle); + + /** + * @brief Callback type for subscribe_changed_param_custom. + */ + using ChangedParamCustomCallback = std::function; + + /** + * @brief Handle type for subscribe_changed_param_custom. + */ + using ChangedParamCustomHandle = Handle; + + /** + * @brief Subscribe to changed custom param. + */ + ChangedParamCustomHandle + subscribe_changed_param_custom(const ChangedParamCustomCallback& callback); + + /** + * @brief Unsubscribe from subscribe_changed_param_custom + */ + void unsubscribe_changed_param_custom(ChangedParamCustomHandle handle); + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/param_server/param_server.cpp b/src/mavsdk/plugins/param_server/param_server.cpp index 7f51c2f3c8..73ad3c44e0 100644 --- a/src/mavsdk/plugins/param_server/param_server.cpp +++ b/src/mavsdk/plugins/param_server/param_server.cpp @@ -57,6 +57,39 @@ ParamServer::AllParams ParamServer::retrieve_all_params() const return _impl->retrieve_all_params(); } +ParamServer::ChangedParamIntHandle +ParamServer::subscribe_changed_param_int(const ChangedParamIntCallback& callback) +{ + return _impl->subscribe_changed_param_int(callback); +} + +void ParamServer::unsubscribe_changed_param_int(ChangedParamIntHandle handle) +{ + _impl->unsubscribe_changed_param_int(handle); +} + +ParamServer::ChangedParamFloatHandle +ParamServer::subscribe_changed_param_float(const ChangedParamFloatCallback& callback) +{ + return _impl->subscribe_changed_param_float(callback); +} + +void ParamServer::unsubscribe_changed_param_float(ChangedParamFloatHandle handle) +{ + _impl->unsubscribe_changed_param_float(handle); +} + +ParamServer::ChangedParamCustomHandle +ParamServer::subscribe_changed_param_custom(const ChangedParamCustomCallback& callback) +{ + return _impl->subscribe_changed_param_custom(callback); +} + +void ParamServer::unsubscribe_changed_param_custom(ChangedParamCustomHandle handle) +{ + _impl->unsubscribe_changed_param_custom(handle); +} + bool operator==(const ParamServer::IntParam& lhs, const ParamServer::IntParam& rhs) { return (rhs.name == lhs.name) && (rhs.value == lhs.value); diff --git a/src/mavsdk/plugins/param_server/param_server_impl.cpp b/src/mavsdk/plugins/param_server/param_server_impl.cpp index efad251b0d..e6c50b19c7 100644 --- a/src/mavsdk/plugins/param_server/param_server_impl.cpp +++ b/src/mavsdk/plugins/param_server/param_server_impl.cpp @@ -1,7 +1,12 @@ #include "param_server_impl.h" +#include "callback_list.tpp" namespace mavsdk { +template class CallbackList; +template class CallbackList; +template class CallbackList; + ParamServerImpl::ParamServerImpl(std::shared_ptr server_component) : ServerPluginImplBase(server_component) { @@ -16,7 +21,10 @@ ParamServerImpl::~ParamServerImpl() void ParamServerImpl::init() {} -void ParamServerImpl::deinit() {} +void ParamServerImpl::deinit() +{ + _server_component_impl->mavlink_parameter_server().unsubscribe_all_params_changed(this); +} std::pair ParamServerImpl::retrieve_param_int(std::string name) const { @@ -36,6 +44,12 @@ ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t return ParamServer::Result::ParamNameTooLong; } _server_component_impl->mavlink_parameter_server().provide_server_param_int(name, value); + _server_component_impl->mavlink_parameter_server().subscribe_param_int_changed( + name, + [name, this](int32_t new_value) { + _changed_param_int_callbacks({name, new_value}); + }, + this); return ParamServer::Result::Success; } @@ -57,6 +71,12 @@ ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float return ParamServer::Result::ParamNameTooLong; } _server_component_impl->mavlink_parameter_server().provide_server_param_float(name, value); + _server_component_impl->mavlink_parameter_server().subscribe_param_float_changed( + name, + [name, this](float new_value) { + _changed_param_float_callbacks({name, new_value}); + }, + this); return ParamServer::Result::Success; } @@ -80,6 +100,12 @@ ParamServerImpl::provide_param_custom(std::string name, const std::string& value return ParamServer::Result::ParamNameTooLong; } _server_component_impl->mavlink_parameter_server().provide_server_param_custom(name, value); + _server_component_impl->mavlink_parameter_server().subscribe_param_custom_changed( + name, + [name, this](std::string new_value) { + _changed_param_custom_callbacks({name, new_value}); + }, + this); return ParamServer::Result::Success; } @@ -106,6 +132,39 @@ ParamServer::AllParams ParamServerImpl::retrieve_all_params() const return res; } +ParamServer::ChangedParamIntHandle +ParamServerImpl::subscribe_changed_param_int(const ParamServer::ChangedParamIntCallback& callback) +{ + return _changed_param_int_callbacks.subscribe(callback); +} + +void ParamServerImpl::unsubscribe_changed_param_int(ParamServer::ChangedParamIntHandle handle) +{ + _changed_param_int_callbacks.unsubscribe(handle); +} + +ParamServer::ChangedParamFloatHandle ParamServerImpl::subscribe_changed_param_float( + const ParamServer::ChangedParamFloatCallback& callback) +{ + return _changed_param_float_callbacks.subscribe(callback); +} + +void ParamServerImpl::unsubscribe_changed_param_float(ParamServer::ChangedParamFloatHandle handle) +{ + _changed_param_float_callbacks.unsubscribe(handle); +} + +ParamServer::ChangedParamCustomHandle ParamServerImpl::subscribe_changed_param_custom( + const ParamServer::ChangedParamCustomCallback& callback) +{ + return _changed_param_custom_callbacks.subscribe(callback); +} + +void ParamServerImpl::unsubscribe_changed_param_custom(ParamServer::ChangedParamCustomHandle handle) +{ + _changed_param_custom_callbacks.unsubscribe(handle); +} + ParamServer::Result ParamServerImpl::result_from_mavlink_parameter_server_result(MavlinkParameterServer::Result result) { diff --git a/src/mavsdk/plugins/param_server/param_server_impl.h b/src/mavsdk/plugins/param_server/param_server_impl.h index c5a7e491bb..ab41ae968e 100644 --- a/src/mavsdk/plugins/param_server/param_server_impl.h +++ b/src/mavsdk/plugins/param_server/param_server_impl.h @@ -3,6 +3,7 @@ #include "plugins/param_server/param_server.h" #include "server_plugin_impl_base.h" #include "mavlink_parameter_server.h" +#include "callback_list.h" namespace mavsdk { @@ -28,10 +29,25 @@ class ParamServerImpl : public ServerPluginImplBase { ParamServer::AllParams retrieve_all_params() const; + ParamServer::ChangedParamIntHandle + subscribe_changed_param_int(const ParamServer::ChangedParamIntCallback& callback); + void unsubscribe_changed_param_int(ParamServer::ChangedParamIntHandle handle); + + ParamServer::ChangedParamFloatHandle + subscribe_changed_param_float(const ParamServer::ChangedParamFloatCallback& callback); + void unsubscribe_changed_param_float(ParamServer::ChangedParamFloatHandle handle); + + ParamServer::ChangedParamCustomHandle + subscribe_changed_param_custom(const ParamServer::ChangedParamCustomCallback& callback); + void unsubscribe_changed_param_custom(ParamServer::ChangedParamCustomHandle handle); + static ParamServer::Result result_from_mavlink_parameter_server_result(MavlinkParameterServer::Result result); private: + CallbackList _changed_param_int_callbacks{}; + CallbackList _changed_param_float_callbacks{}; + CallbackList _changed_param_custom_callbacks{}; }; } // namespace mavsdk diff --git a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc index bf3efe5a00..e18f439870 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc @@ -31,6 +31,9 @@ static const char* ParamServerService_method_names[] = { "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamCustom", "/mavsdk.rpc.param_server.ParamServerService/ProvideParamCustom", "/mavsdk.rpc.param_server.ParamServerService/RetrieveAllParams", + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamInt", + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamFloat", + "/mavsdk.rpc.param_server.ParamServerService/SubscribeChangedParamCustom", }; std::unique_ptr< ParamServerService::Stub> ParamServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -47,6 +50,9 @@ ParamServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& , rpcmethod_RetrieveParamCustom_(ParamServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_ProvideParamCustom_(ParamServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_RetrieveAllParams_(ParamServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeChangedParamInt_(ParamServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeChangedParamFloat_(ParamServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeChangedParamCustom_(ParamServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::Status ParamServerService::Stub::RetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response) { @@ -210,6 +216,54 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveAllParam return result; } +::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* ParamServerService::Stub::SubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::param_server::ChangedParamIntResponse>::Create(channel_.get(), rpcmethod_SubscribeChangedParamInt_, context, request); +} + +void ParamServerService::Stub::async::SubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::param_server::ChangedParamIntResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeChangedParamInt_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* ParamServerService::Stub::AsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamIntResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamInt_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* ParamServerService::Stub::PrepareAsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamIntResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamInt_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* ParamServerService::Stub::SubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>::Create(channel_.get(), rpcmethod_SubscribeChangedParamFloat_, context, request); +} + +void ParamServerService::Stub::async::SubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeChangedParamFloat_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* ParamServerService::Stub::AsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamFloat_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* ParamServerService::Stub::PrepareAsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamFloat_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* ParamServerService::Stub::SubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>::Create(channel_.get(), rpcmethod_SubscribeChangedParamCustom_, context, request); +} + +void ParamServerService::Stub::async::SubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeChangedParamCustom_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* ParamServerService::Stub::AsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamCustom_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* ParamServerService::Stub::PrepareAsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeChangedParamCustom_, context, request, false, nullptr); +} + ParamServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( ParamServerService_method_names[0], @@ -281,6 +335,36 @@ ParamServerService::Service::Service() { ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* resp) { return service->RetrieveAllParams(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ParamServerService_method_names[7], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( + [](ParamServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::param_server::ChangedParamIntResponse>* writer) { + return service->SubscribeChangedParamInt(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ParamServerService_method_names[8], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( + [](ParamServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::param_server::ChangedParamFloatResponse>* writer) { + return service->SubscribeChangedParamFloat(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ParamServerService_method_names[9], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( + [](ParamServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer) { + return service->SubscribeChangedParamCustom(ctx, req, writer); + }, this))); } ParamServerService::Service::~Service() { @@ -335,6 +419,27 @@ ::grpc::Status ParamServerService::Service::RetrieveAllParams(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status ParamServerService::Service::SubscribeChangedParamInt(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status ParamServerService::Service::SubscribeChangedParamFloat(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status ParamServerService::Service::SubscribeChangedParamCustom(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h index 15c503de02..930d5c223c 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h @@ -113,6 +113,36 @@ class ParamServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>> PrepareAsyncRetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>>(PrepareAsyncRetrieveAllParamsRaw(context, request, cq)); } + // Subscribe to changed int param. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> SubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(SubscribeChangedParamIntRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> AsyncSubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(AsyncSubscribeChangedParamIntRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> PrepareAsyncSubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(PrepareAsyncSubscribeChangedParamIntRaw(context, request, cq)); + } + // Subscribe to changed float param. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> SubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(SubscribeChangedParamFloatRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> AsyncSubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(AsyncSubscribeChangedParamFloatRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> PrepareAsyncSubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(PrepareAsyncSubscribeChangedParamFloatRaw(context, request, cq)); + } + // Subscribe to changed custom param. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> SubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(SubscribeChangedParamCustomRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> AsyncSubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(AsyncSubscribeChangedParamCustomRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> PrepareAsyncSubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(PrepareAsyncSubscribeChangedParamCustomRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -156,6 +186,12 @@ class ParamServerService final { // Retrieve all parameters. virtual void RetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response, std::function) = 0; virtual void RetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Subscribe to changed int param. + virtual void SubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* reactor) = 0; + // Subscribe to changed float param. + virtual void SubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* reactor) = 0; + // Subscribe to changed custom param. + virtual void SubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -175,6 +211,15 @@ class ParamServerService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::ProvideParamCustomResponse>* PrepareAsyncProvideParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamCustomRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* AsyncRetrieveAllParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* PrepareAsyncRetrieveAllParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* SubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* AsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* PrepareAsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* SubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* AsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* PrepareAsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* SubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* AsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* PrepareAsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -228,6 +273,33 @@ class ParamServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>> PrepareAsyncRetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>>(PrepareAsyncRetrieveAllParamsRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> SubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(SubscribeChangedParamIntRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> AsyncSubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(AsyncSubscribeChangedParamIntRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>> PrepareAsyncSubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>>(PrepareAsyncSubscribeChangedParamIntRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> SubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(SubscribeChangedParamFloatRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> AsyncSubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(AsyncSubscribeChangedParamFloatRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>> PrepareAsyncSubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>>(PrepareAsyncSubscribeChangedParamFloatRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> SubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(SubscribeChangedParamCustomRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> AsyncSubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(AsyncSubscribeChangedParamCustomRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>> PrepareAsyncSubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>>(PrepareAsyncSubscribeChangedParamCustomRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -245,6 +317,9 @@ class ParamServerService final { void ProvideParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamCustomRequest* request, ::mavsdk::rpc::param_server::ProvideParamCustomResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void RetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response, std::function) override; void RetrieveAllParams(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeChangedParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* reactor) override; + void SubscribeChangedParamFloat(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* reactor) override; + void SubscribeChangedParamCustom(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -270,6 +345,15 @@ class ParamServerService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::ProvideParamCustomResponse>* PrepareAsyncProvideParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamCustomRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* AsyncRetrieveAllParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* PrepareAsyncRetrieveAllParamsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* SubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* AsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* PrepareAsyncSubscribeChangedParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* SubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* AsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* PrepareAsyncSubscribeChangedParamFloatRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* SubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* AsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* PrepareAsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_RetrieveParamInt_; const ::grpc::internal::RpcMethod rpcmethod_ProvideParamInt_; const ::grpc::internal::RpcMethod rpcmethod_RetrieveParamFloat_; @@ -277,6 +361,9 @@ class ParamServerService final { const ::grpc::internal::RpcMethod rpcmethod_RetrieveParamCustom_; const ::grpc::internal::RpcMethod rpcmethod_ProvideParamCustom_; const ::grpc::internal::RpcMethod rpcmethod_RetrieveAllParams_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeChangedParamInt_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeChangedParamFloat_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeChangedParamCustom_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -317,6 +404,12 @@ class ParamServerService final { // // Retrieve all parameters. virtual ::grpc::Status RetrieveAllParams(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response); + // Subscribe to changed int param. + virtual ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* writer); + // Subscribe to changed float param. + virtual ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* writer); + // Subscribe to changed custom param. + virtual ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer); }; template class WithAsyncMethod_RetrieveParamInt : public BaseClass { @@ -458,7 +551,67 @@ class ParamServerService final { ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_RetrieveParamInt > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodAsync(7); + } + ~WithAsyncMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamInt(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodAsync(8); + } + ~WithAsyncMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamFloat(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodAsync(9); + } + ~WithAsyncMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamCustom(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_RetrieveParamInt > > > > > > > > > AsyncService; template class WithCallbackMethod_RetrieveParamInt : public BaseClass { private: @@ -648,7 +801,73 @@ class ParamServerService final { virtual ::grpc::ServerUnaryReactor* RetrieveAllParams( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* /*request*/, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_RetrieveParamInt > > > > > > CallbackService; + template + class WithCallbackMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodCallback(7, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request) { return this->SubscribeChangedParamInt(context, request); })); + } + ~WithCallbackMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* SubscribeChangedParamInt( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodCallback(8, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request) { return this->SubscribeChangedParamFloat(context, request); })); + } + ~WithCallbackMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* SubscribeChangedParamFloat( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request) { return this->SubscribeChangedParamCustom(context, request); })); + } + ~WithCallbackMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* SubscribeChangedParamCustom( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/) { return nullptr; } + }; + typedef WithCallbackMethod_RetrieveParamInt > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_RetrieveParamInt : public BaseClass { @@ -770,6 +989,57 @@ class ParamServerService final { } }; template + class WithGenericMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodGeneric(7); + } + ~WithGenericMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodGeneric(8); + } + ~WithGenericMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodGeneric(9); + } + ~WithGenericMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -910,6 +1180,66 @@ class ParamServerService final { } }; template + class WithRawMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodRaw(7); + } + ~WithRawMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamInt(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodRaw(8); + } + ~WithRawMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamFloat(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeChangedParamCustom(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1064,6 +1394,72 @@ class ParamServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodRawCallback(7, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamInt(context, request); })); + } + ~WithRawCallbackMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeChangedParamInt( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodRawCallback(8, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamFloat(context, request); })); + } + ~WithRawCallbackMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeChangedParamFloat( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodRawCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamCustom(context, request); })); + } + ~WithRawCallbackMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeChangedParamCustom( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1253,8 +1649,89 @@ class ParamServerService final { virtual ::grpc::Status StreamedRetrieveAllParams(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest,::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* server_unary_streamer) = 0; }; typedef WithStreamedUnaryMethod_RetrieveParamInt > > > > > > StreamedUnaryService; - typedef Service SplitStreamedService; - typedef WithStreamedUnaryMethod_RetrieveParamInt > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeChangedParamInt : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeChangedParamInt() { + ::grpc::Service::MarkMethodStreamed(7, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>* streamer) { + return this->StreamedSubscribeChangedParamInt(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeChangedParamInt() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeChangedParamInt(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeChangedParamInt(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest,::mavsdk::rpc::param_server::ChangedParamIntResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeChangedParamFloat : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeChangedParamFloat() { + ::grpc::Service::MarkMethodStreamed(8, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* streamer) { + return this->StreamedSubscribeChangedParamFloat(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeChangedParamFloat() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeChangedParamFloat(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeChangedParamFloat(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest,::mavsdk::rpc::param_server::ChangedParamFloatResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeChangedParamCustom : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeChangedParamCustom() { + ::grpc::Service::MarkMethodStreamed(9, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* streamer) { + return this->StreamedSubscribeChangedParamCustom(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeChangedParamCustom() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeChangedParamCustom(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest,::mavsdk::rpc::param_server::ChangedParamCustomResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribeChangedParamInt > > SplitStreamedService; + typedef WithStreamedUnaryMethod_RetrieveParamInt > > > > > > > > > StreamedService; }; } // namespace param_server diff --git a/src/mavsdk_server/src/generated/param_server/param_server.pb.cc b/src/mavsdk_server/src/generated/param_server/param_server.pb.cc index 75ae773861..19aa7b41fd 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.pb.cc +++ b/src/mavsdk_server/src/generated/param_server/param_server.pb.cc @@ -271,6 +271,93 @@ struct RetrieveAllParamsResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 RetrieveAllParamsResponseDefaultTypeInternal _RetrieveAllParamsResponse_default_instance_; template +PROTOBUF_CONSTEXPR SubscribeChangedParamIntRequest::SubscribeChangedParamIntRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeChangedParamIntRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeChangedParamIntRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeChangedParamIntRequestDefaultTypeInternal() {} + union { + SubscribeChangedParamIntRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeChangedParamIntRequestDefaultTypeInternal _SubscribeChangedParamIntRequest_default_instance_; +template +PROTOBUF_CONSTEXPR ChangedParamIntResponse::ChangedParamIntResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.param_)*/nullptr} {} +struct ChangedParamIntResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ChangedParamIntResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ChangedParamIntResponseDefaultTypeInternal() {} + union { + ChangedParamIntResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ChangedParamIntResponseDefaultTypeInternal _ChangedParamIntResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeChangedParamFloatRequest::SubscribeChangedParamFloatRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeChangedParamFloatRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeChangedParamFloatRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeChangedParamFloatRequestDefaultTypeInternal() {} + union { + SubscribeChangedParamFloatRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeChangedParamFloatRequestDefaultTypeInternal _SubscribeChangedParamFloatRequest_default_instance_; +template +PROTOBUF_CONSTEXPR ChangedParamFloatResponse::ChangedParamFloatResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.param_)*/nullptr} {} +struct ChangedParamFloatResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ChangedParamFloatResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ChangedParamFloatResponseDefaultTypeInternal() {} + union { + ChangedParamFloatResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ChangedParamFloatResponseDefaultTypeInternal _ChangedParamFloatResponse_default_instance_; +template +PROTOBUF_CONSTEXPR SubscribeChangedParamCustomRequest::SubscribeChangedParamCustomRequest( + ::_pbi::ConstantInitialized) {} +struct SubscribeChangedParamCustomRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeChangedParamCustomRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeChangedParamCustomRequestDefaultTypeInternal() {} + union { + SubscribeChangedParamCustomRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeChangedParamCustomRequestDefaultTypeInternal _SubscribeChangedParamCustomRequest_default_instance_; +template +PROTOBUF_CONSTEXPR ChangedParamCustomResponse::ChangedParamCustomResponse( + ::_pbi::ConstantInitialized): _impl_{ + /*decltype(_impl_._has_bits_)*/{} + , /*decltype(_impl_._cached_size_)*/{} + , /*decltype(_impl_.param_)*/nullptr} {} +struct ChangedParamCustomResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ChangedParamCustomResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ChangedParamCustomResponseDefaultTypeInternal() {} + union { + ChangedParamCustomResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ChangedParamCustomResponseDefaultTypeInternal _ChangedParamCustomResponse_default_instance_; +template PROTOBUF_CONSTEXPR IntParam::IntParam( ::_pbi::ConstantInitialized): _impl_{ /*decltype(_impl_.name_)*/ { @@ -372,7 +459,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace param_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[19]; +static ::_pb::Metadata file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[25]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_param_5fserver_2fparam_5fserver_2eproto[1]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_param_5fserver_2fparam_5fserver_2eproto = nullptr; @@ -520,6 +607,60 @@ const ::uint32_t TableStruct_param_5fserver_2fparam_5fserver_2eproto::offsets[] PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::RetrieveAllParamsResponse, _impl_.params_), 0, ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, _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::param_server::ChangedParamIntResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::ChangedParamIntResponse, _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::param_server::ChangedParamIntResponse, _impl_.param_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, _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::param_server::ChangedParamFloatResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::ChangedParamFloatResponse, _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::param_server::ChangedParamFloatResponse, _impl_.param_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, _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::param_server::ChangedParamCustomResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::ChangedParamCustomResponse, _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::param_server::ChangedParamCustomResponse, _impl_.param_), + 0, + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::IntParam, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -588,11 +729,17 @@ static const ::_pbi::MigrationSchema { 113, 122, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamCustomResponse)}, { 123, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsRequest)}, { 131, 140, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsResponse)}, - { 141, -1, -1, sizeof(::mavsdk::rpc::param_server::IntParam)}, - { 151, -1, -1, sizeof(::mavsdk::rpc::param_server::FloatParam)}, - { 161, -1, -1, sizeof(::mavsdk::rpc::param_server::CustomParam)}, - { 171, -1, -1, sizeof(::mavsdk::rpc::param_server::AllParams)}, - { 182, -1, -1, sizeof(::mavsdk::rpc::param_server::ParamServerResult)}, + { 141, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest)}, + { 149, 158, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamIntResponse)}, + { 159, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest)}, + { 167, 176, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamFloatResponse)}, + { 177, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest)}, + { 185, 194, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamCustomResponse)}, + { 195, -1, -1, sizeof(::mavsdk::rpc::param_server::IntParam)}, + { 205, -1, -1, sizeof(::mavsdk::rpc::param_server::FloatParam)}, + { 215, -1, -1, sizeof(::mavsdk::rpc::param_server::CustomParam)}, + { 225, -1, -1, sizeof(::mavsdk::rpc::param_server::AllParams)}, + { 236, -1, -1, sizeof(::mavsdk::rpc::param_server::ParamServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -610,6 +757,12 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::param_server::_ProvideParamCustomResponse_default_instance_._instance, &::mavsdk::rpc::param_server::_RetrieveAllParamsRequest_default_instance_._instance, &::mavsdk::rpc::param_server::_RetrieveAllParamsResponse_default_instance_._instance, + &::mavsdk::rpc::param_server::_SubscribeChangedParamIntRequest_default_instance_._instance, + &::mavsdk::rpc::param_server::_ChangedParamIntResponse_default_instance_._instance, + &::mavsdk::rpc::param_server::_SubscribeChangedParamFloatRequest_default_instance_._instance, + &::mavsdk::rpc::param_server::_ChangedParamFloatResponse_default_instance_._instance, + &::mavsdk::rpc::param_server::_SubscribeChangedParamCustomRequest_default_instance_._instance, + &::mavsdk::rpc::param_server::_ChangedParamCustomResponse_default_instance_._instance, &::mavsdk::rpc::param_server::_IntParam_default_instance_._instance, &::mavsdk::rpc::param_server::_FloatParam_default_instance_._instance, &::mavsdk::rpc::param_server::_CustomParam_default_instance_._instance, @@ -645,47 +798,67 @@ const char descriptor_table_protodef_param_5fserver_2fparam_5fserver_2eproto[] P "k.rpc.param_server.ParamServerResult\"\032\n\030" "RetrieveAllParamsRequest\"O\n\031RetrieveAllP" "aramsResponse\0222\n\006params\030\001 \001(\0132\".mavsdk.r" - "pc.param_server.AllParams\"\'\n\010IntParam\022\014\n" - "\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\005\")\n\nFloatParam" - "\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\002\"*\n\013CustomP" - "aram\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\t\"\272\001\n\tAl" - "lParams\0225\n\nint_params\030\001 \003(\0132!.mavsdk.rpc" - ".param_server.IntParam\0229\n\014float_params\030\002" - " \003(\0132#.mavsdk.rpc.param_server.FloatPara" - "m\022;\n\rcustom_params\030\003 \003(\0132$.mavsdk.rpc.pa" - "ram_server.CustomParam\"\241\002\n\021ParamServerRe" - "sult\022A\n\006result\030\001 \001(\01621.mavsdk.rpc.param_" - "server.ParamServerResult.Result\022\022\n\nresul" - "t_str\030\002 \001(\t\"\264\001\n\006Result\022\022\n\016RESULT_UNKNOWN" - "\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NOT_FOU" - "ND\020\002\022\025\n\021RESULT_WRONG_TYPE\020\003\022\036\n\032RESULT_PA" - "RAM_NAME_TOO_LONG\020\004\022\024\n\020RESULT_NO_SYSTEM\020" - "\005\022\037\n\033RESULT_PARAM_VALUE_TOO_LONG\020\0062\252\007\n\022P" - "aramServerService\022}\n\020RetrieveParamInt\0220." - "mavsdk.rpc.param_server.RetrieveParamInt" - "Request\0321.mavsdk.rpc.param_server.Retrie" - "veParamIntResponse\"\004\200\265\030\001\022z\n\017ProvideParam" - "Int\022/.mavsdk.rpc.param_server.ProvidePar" - "amIntRequest\0320.mavsdk.rpc.param_server.P" - "rovideParamIntResponse\"\004\200\265\030\001\022\203\001\n\022Retriev" - "eParamFloat\0222.mavsdk.rpc.param_server.Re" - "trieveParamFloatRequest\0323.mavsdk.rpc.par" - "am_server.RetrieveParamFloatResponse\"\004\200\265" - "\030\001\022\200\001\n\021ProvideParamFloat\0221.mavsdk.rpc.pa" - "ram_server.ProvideParamFloatRequest\0322.ma" - "vsdk.rpc.param_server.ProvideParamFloatR" - "esponse\"\004\200\265\030\001\022\206\001\n\023RetrieveParamCustom\0223." - "mavsdk.rpc.param_server.RetrieveParamCus" - "tomRequest\0324.mavsdk.rpc.param_server.Ret" - "rieveParamCustomResponse\"\004\200\265\030\001\022\203\001\n\022Provi" - "deParamCustom\0222.mavsdk.rpc.param_server." - "ProvideParamCustomRequest\0323.mavsdk.rpc.p" - "aram_server.ProvideParamCustomResponse\"\004" - "\200\265\030\001\022\200\001\n\021RetrieveAllParams\0221.mavsdk.rpc." - "param_server.RetrieveAllParamsRequest\0322." - "mavsdk.rpc.param_server.RetrieveAllParam" - "sResponse\"\004\200\265\030\001B*\n\026io.mavsdk.param_serve" - "rB\020ParamServerProtob\006proto3" + "pc.param_server.AllParams\"!\n\037SubscribeCh" + "angedParamIntRequest\"K\n\027ChangedParamIntR" + "esponse\0220\n\005param\030\001 \001(\0132!.mavsdk.rpc.para" + "m_server.IntParam\"#\n!SubscribeChangedPar" + "amFloatRequest\"O\n\031ChangedParamFloatRespo" + "nse\0222\n\005param\030\001 \001(\0132#.mavsdk.rpc.param_se" + "rver.FloatParam\"$\n\"SubscribeChangedParam" + "CustomRequest\"Q\n\032ChangedParamCustomRespo" + "nse\0223\n\005param\030\001 \001(\0132$.mavsdk.rpc.param_se" + "rver.CustomParam\"\'\n\010IntParam\022\014\n\004name\030\001 \001" + "(\t\022\r\n\005value\030\002 \001(\005\")\n\nFloatParam\022\014\n\004name\030" + "\001 \001(\t\022\r\n\005value\030\002 \001(\002\"*\n\013CustomParam\022\014\n\004n" + "ame\030\001 \001(\t\022\r\n\005value\030\002 \001(\t\"\272\001\n\tAllParams\0225" + "\n\nint_params\030\001 \003(\0132!.mavsdk.rpc.param_se" + "rver.IntParam\0229\n\014float_params\030\002 \003(\0132#.ma" + "vsdk.rpc.param_server.FloatParam\022;\n\rcust" + "om_params\030\003 \003(\0132$.mavsdk.rpc.param_serve" + "r.CustomParam\"\241\002\n\021ParamServerResult\022A\n\006r" + "esult\030\001 \001(\01621.mavsdk.rpc.param_server.Pa" + "ramServerResult.Result\022\022\n\nresult_str\030\002 \001" + "(\t\"\264\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RES" + "ULT_SUCCESS\020\001\022\024\n\020RESULT_NOT_FOUND\020\002\022\025\n\021R" + "ESULT_WRONG_TYPE\020\003\022\036\n\032RESULT_PARAM_NAME_" + "TOO_LONG\020\004\022\024\n\020RESULT_NO_SYSTEM\020\005\022\037\n\033RESU" + "LT_PARAM_VALUE_TOO_LONG\020\0062\354\n\n\022ParamServe" + "rService\022}\n\020RetrieveParamInt\0220.mavsdk.rp" + "c.param_server.RetrieveParamIntRequest\0321" + ".mavsdk.rpc.param_server.RetrieveParamIn" + "tResponse\"\004\200\265\030\001\022z\n\017ProvideParamInt\022/.mav" + "sdk.rpc.param_server.ProvideParamIntRequ" + "est\0320.mavsdk.rpc.param_server.ProvidePar" + "amIntResponse\"\004\200\265\030\001\022\203\001\n\022RetrieveParamFlo" + "at\0222.mavsdk.rpc.param_server.RetrievePar" + "amFloatRequest\0323.mavsdk.rpc.param_server" + ".RetrieveParamFloatResponse\"\004\200\265\030\001\022\200\001\n\021Pr" + "ovideParamFloat\0221.mavsdk.rpc.param_serve" + "r.ProvideParamFloatRequest\0322.mavsdk.rpc." + "param_server.ProvideParamFloatResponse\"\004" + "\200\265\030\001\022\206\001\n\023RetrieveParamCustom\0223.mavsdk.rp" + "c.param_server.RetrieveParamCustomReques" + "t\0324.mavsdk.rpc.param_server.RetrievePara" + "mCustomResponse\"\004\200\265\030\001\022\203\001\n\022ProvideParamCu" + "stom\0222.mavsdk.rpc.param_server.ProvidePa" + "ramCustomRequest\0323.mavsdk.rpc.param_serv" + "er.ProvideParamCustomResponse\"\004\200\265\030\001\022\200\001\n\021" + "RetrieveAllParams\0221.mavsdk.rpc.param_ser" + "ver.RetrieveAllParamsRequest\0322.mavsdk.rp" + "c.param_server.RetrieveAllParamsResponse" + "\"\004\200\265\030\001\022\216\001\n\030SubscribeChangedParamInt\0228.ma" + "vsdk.rpc.param_server.SubscribeChangedPa" + "ramIntRequest\0320.mavsdk.rpc.param_server." + "ChangedParamIntResponse\"\004\200\265\030\0000\001\022\224\001\n\032Subs" + "cribeChangedParamFloat\022:.mavsdk.rpc.para" + "m_server.SubscribeChangedParamFloatReque" + "st\0322.mavsdk.rpc.param_server.ChangedPara" + "mFloatResponse\"\004\200\265\030\0000\001\022\227\001\n\033SubscribeChan" + "gedParamCustom\022;.mavsdk.rpc.param_server" + ".SubscribeChangedParamCustomRequest\0323.ma" + "vsdk.rpc.param_server.ChangedParamCustom" + "Response\"\004\200\265\030\0000\001B*\n\026io.mavsdk.param_serv" + "erB\020ParamServerProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_param_5fserver_2fparam_5fserver_2eproto_deps[1] = { @@ -695,13 +868,13 @@ static ::absl::once_flag descriptor_table_param_5fserver_2fparam_5fserver_2eprot const ::_pbi::DescriptorTable descriptor_table_param_5fserver_2fparam_5fserver_2eproto = { false, false, - 2747, + 3548, descriptor_table_protodef_param_5fserver_2fparam_5fserver_2eproto, "param_server/param_server.proto", &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, descriptor_table_param_5fserver_2fparam_5fserver_2eproto_deps, 1, - 19, + 25, schemas, file_default_instances, TableStruct_param_5fserver_2fparam_5fserver_2eproto::offsets, @@ -3671,54 +3844,90 @@ ::PROTOBUF_NAMESPACE_ID::Metadata RetrieveAllParamsResponse::GetMetadata() const } // =================================================================== -class IntParam::_Internal { +class SubscribeChangedParamIntRequest::_Internal { public: }; -IntParam::IntParam(::PROTOBUF_NAMESPACE_ID::Arena* arena) +SubscribeChangedParamIntRequest::SubscribeChangedParamIntRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.SubscribeChangedParamIntRequest) +} +SubscribeChangedParamIntRequest::SubscribeChangedParamIntRequest(const SubscribeChangedParamIntRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeChangedParamIntRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.SubscribeChangedParamIntRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeChangedParamIntRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeChangedParamIntRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeChangedParamIntRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[14]); +} +// =================================================================== + +class ChangedParamIntResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ChangedParamIntResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::param_server::IntParam& param(const ChangedParamIntResponse* msg); + static void set_has_param(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::param_server::IntParam& +ChangedParamIntResponse::_Internal::param(const ChangedParamIntResponse* msg) { + return *msg->_impl_.param_; +} +ChangedParamIntResponse::ChangedParamIntResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) : ::PROTOBUF_NAMESPACE_ID::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.IntParam) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.ChangedParamIntResponse) } -IntParam::IntParam(const IntParam& from) +ChangedParamIntResponse::ChangedParamIntResponse(const ChangedParamIntResponse& from) : ::PROTOBUF_NAMESPACE_ID::Message() { - IntParam* const _this = this; (void)_this; + ChangedParamIntResponse* const _this = this; (void)_this; new (&_impl_) Impl_{ - decltype(_impl_.name_) {} - - , decltype(_impl_.value_) {} - - , /*decltype(_impl_._cached_size_)*/{}}; + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr}}; _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); - _impl_.name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING - if (!from._internal_name().empty()) { - _this->_impl_.name_.Set(from._internal_name(), _this->GetArenaForAllocation()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.param_ = new ::mavsdk::rpc::param_server::IntParam(*from._impl_.param_); } - _this->_impl_.value_ = from._impl_.value_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.IntParam) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.ChangedParamIntResponse) } -inline void IntParam::SharedCtor(::_pb::Arena* arena) { +inline void ChangedParamIntResponse::SharedCtor(::_pb::Arena* arena) { (void)arena; new (&_impl_) Impl_{ - decltype(_impl_.name_) {} - - , decltype(_impl_.value_) { 0 } - + decltype(_impl_._has_bits_){} , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr} }; - _impl_.name_.InitDefault(); - #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING - _impl_.name_.Set("", GetArenaForAllocation()); - #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING } -IntParam::~IntParam() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.IntParam) +ChangedParamIntResponse::~ChangedParamIntResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.ChangedParamIntResponse) if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { (void)arena; return; @@ -3726,47 +3935,41 @@ IntParam::~IntParam() { SharedDtor(); } -inline void IntParam::SharedDtor() { +inline void ChangedParamIntResponse::SharedDtor() { ABSL_DCHECK(GetArenaForAllocation() == nullptr); - _impl_.name_.Destroy(); + if (this != internal_default_instance()) delete _impl_.param_; } -void IntParam::SetCachedSize(int size) const { +void ChangedParamIntResponse::SetCachedSize(int size) const { _impl_._cached_size_.Set(size); } -void IntParam::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.IntParam) +void ChangedParamIntResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.ChangedParamIntResponse) ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.name_.ClearToEmpty(); - _impl_.value_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.param_ != nullptr); + _impl_.param_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } -const char* IntParam::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +const char* ChangedParamIntResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { #define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; while (!ctx->Done(&ptr)) { ::uint32_t tag; ptr = ::_pbi::ReadTag(ptr, &tag); switch (tag >> 3) { - // string name = 1; + // .mavsdk.rpc.param_server.IntParam param = 1; case 1: if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { - auto str = _internal_mutable_name(); - ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); - CHK_(ptr); - CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.param_server.IntParam.name")); - } else { - goto handle_unusual; - } - continue; - // int32 value = 2; - case 2: - if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 16)) { - _impl_.value_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + ptr = ctx->ParseMessage(_internal_mutable_param(), ptr); CHK_(ptr); } else { goto handle_unusual; @@ -3788,6 +3991,7 @@ const char* IntParam::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) CHK_(ptr != nullptr); } // while message_done: + _impl_._has_bits_.Or(has_bits); return ptr; failure: ptr = nullptr; @@ -3795,125 +3999,823 @@ const char* IntParam::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) #undef CHK_ } -::uint8_t* IntParam::_InternalSerialize( +::uint8_t* ChangedParamIntResponse::_InternalSerialize( ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.IntParam) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.ChangedParamIntResponse) ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - // string name = 1; - if (!this->_internal_name().empty()) { - const std::string& _s = this->_internal_name(); - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( - _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.param_server.IntParam.name"); - target = stream->WriteStringMaybeAliased(1, _s, target); - } - - // int32 value = 2; - if (this->_internal_value() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteInt32ToArray( - 2, this->_internal_value(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.param_server.IntParam param = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::param(this), + _Internal::param(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.param_server.IntParam) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.param_server.ChangedParamIntResponse) return target; } -::size_t IntParam::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.IntParam) +::size_t ChangedParamIntResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.ChangedParamIntResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string name = 1; - if (!this->_internal_name().empty()) { - total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( - this->_internal_name()); - } - - // int32 value = 2; - if (this->_internal_value() != 0) { - total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_value()); + // .mavsdk.rpc.param_server.IntParam param = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.param_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData IntParam::_class_data_ = { +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ChangedParamIntResponse::_class_data_ = { ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, - IntParam::MergeImpl + ChangedParamIntResponse::MergeImpl }; -const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*IntParam::GetClassData() const { return &_class_data_; } +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ChangedParamIntResponse::GetClassData() const { return &_class_data_; } -void IntParam::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.param_server.IntParam) +void ChangedParamIntResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.param_server.ChangedParamIntResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (!from._internal_name().empty()) { - _this->_internal_set_name(from._internal_name()); - } - if (from._internal_value() != 0) { - _this->_internal_set_value(from._internal_value()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_param()->::mavsdk::rpc::param_server::IntParam::MergeFrom( + from._internal_param()); } _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } -void IntParam::CopyFrom(const IntParam& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.IntParam) +void ChangedParamIntResponse::CopyFrom(const ChangedParamIntResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.ChangedParamIntResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool IntParam::IsInitialized() const { +bool ChangedParamIntResponse::IsInitialized() const { return true; } -void IntParam::InternalSwap(IntParam* other) { +void ChangedParamIntResponse::InternalSwap(ChangedParamIntResponse* other) { using std::swap; - auto* lhs_arena = GetArenaForAllocation(); - auto* rhs_arena = other->GetArenaForAllocation(); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.name_, lhs_arena, - &other->_impl_.name_, rhs_arena); - - swap(_impl_.value_, other->_impl_.value_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.param_, other->_impl_.param_); } -::PROTOBUF_NAMESPACE_ID::Metadata IntParam::GetMetadata() const { +::PROTOBUF_NAMESPACE_ID::Metadata ChangedParamIntResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[14]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[15]); } // =================================================================== -class FloatParam::_Internal { +class SubscribeChangedParamFloatRequest::_Internal { public: }; -FloatParam::FloatParam(::PROTOBUF_NAMESPACE_ID::Arena* arena) - : ::PROTOBUF_NAMESPACE_ID::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.FloatParam) +SubscribeChangedParamFloatRequest::SubscribeChangedParamFloatRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest) } -FloatParam::FloatParam(const FloatParam& from) - : ::PROTOBUF_NAMESPACE_ID::Message() { - FloatParam* const _this = this; (void)_this; - new (&_impl_) Impl_{ - decltype(_impl_.name_) {} +SubscribeChangedParamFloatRequest::SubscribeChangedParamFloatRequest(const SubscribeChangedParamFloatRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeChangedParamFloatRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeChangedParamFloatRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeChangedParamFloatRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeChangedParamFloatRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[16]); +} +// =================================================================== + +class ChangedParamFloatResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ChangedParamFloatResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::param_server::FloatParam& param(const ChangedParamFloatResponse* msg); + static void set_has_param(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::param_server::FloatParam& +ChangedParamFloatResponse::_Internal::param(const ChangedParamFloatResponse* msg) { + return *msg->_impl_.param_; +} +ChangedParamFloatResponse::ChangedParamFloatResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.ChangedParamFloatResponse) +} +ChangedParamFloatResponse::ChangedParamFloatResponse(const ChangedParamFloatResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + ChangedParamFloatResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.param_ = new ::mavsdk::rpc::param_server::FloatParam(*from._impl_.param_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.ChangedParamFloatResponse) +} + +inline void ChangedParamFloatResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr} + }; +} + +ChangedParamFloatResponse::~ChangedParamFloatResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.ChangedParamFloatResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void ChangedParamFloatResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.param_; +} + +void ChangedParamFloatResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void ChangedParamFloatResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.ChangedParamFloatResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.param_ != nullptr); + _impl_.param_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ChangedParamFloatResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.param_server.FloatParam param = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_param(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* ChangedParamFloatResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.ChangedParamFloatResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.param_server.FloatParam param = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::param(this), + _Internal::param(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.param_server.ChangedParamFloatResponse) + return target; +} + +::size_t ChangedParamFloatResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.ChangedParamFloatResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.param_server.FloatParam param = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.param_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ChangedParamFloatResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + ChangedParamFloatResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ChangedParamFloatResponse::GetClassData() const { return &_class_data_; } + + +void ChangedParamFloatResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.param_server.ChangedParamFloatResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_param()->::mavsdk::rpc::param_server::FloatParam::MergeFrom( + from._internal_param()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ChangedParamFloatResponse::CopyFrom(const ChangedParamFloatResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.ChangedParamFloatResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ChangedParamFloatResponse::IsInitialized() const { + return true; +} + +void ChangedParamFloatResponse::InternalSwap(ChangedParamFloatResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.param_, other->_impl_.param_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ChangedParamFloatResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[17]); +} +// =================================================================== + +class SubscribeChangedParamCustomRequest::_Internal { + public: +}; + +SubscribeChangedParamCustomRequest::SubscribeChangedParamCustomRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest) +} +SubscribeChangedParamCustomRequest::SubscribeChangedParamCustomRequest(const SubscribeChangedParamCustomRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + SubscribeChangedParamCustomRequest* const _this = this; (void)_this; + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeChangedParamCustomRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeChangedParamCustomRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::Metadata SubscribeChangedParamCustomRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[18]); +} +// =================================================================== + +class ChangedParamCustomResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ChangedParamCustomResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::param_server::CustomParam& param(const ChangedParamCustomResponse* msg); + static void set_has_param(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::param_server::CustomParam& +ChangedParamCustomResponse::_Internal::param(const ChangedParamCustomResponse* msg) { + return *msg->_impl_.param_; +} +ChangedParamCustomResponse::ChangedParamCustomResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.ChangedParamCustomResponse) +} +ChangedParamCustomResponse::ChangedParamCustomResponse(const ChangedParamCustomResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + ChangedParamCustomResponse* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){from._impl_._has_bits_} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_impl_.param_ = new ::mavsdk::rpc::param_server::CustomParam(*from._impl_.param_); + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.ChangedParamCustomResponse) +} + +inline void ChangedParamCustomResponse::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_._has_bits_){} + , /*decltype(_impl_._cached_size_)*/{} + , decltype(_impl_.param_){nullptr} + }; +} + +ChangedParamCustomResponse::~ChangedParamCustomResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.ChangedParamCustomResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void ChangedParamCustomResponse::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete _impl_.param_; +} + +void ChangedParamCustomResponse::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void ChangedParamCustomResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.ChangedParamCustomResponse) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.param_ != nullptr); + _impl_.param_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* ChangedParamCustomResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + _Internal::HasBits has_bits{}; + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.param_server.CustomParam param = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_param(), ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + _impl_._has_bits_.Or(has_bits); + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* ChangedParamCustomResponse::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.ChangedParamCustomResponse) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.param_server.CustomParam param = 1; + if (cached_has_bits & 0x00000001u) { + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage(1, _Internal::param(this), + _Internal::param(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.param_server.ChangedParamCustomResponse) + return target; +} + +::size_t ChangedParamCustomResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.ChangedParamCustomResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.param_server.CustomParam param = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *_impl_.param_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData ChangedParamCustomResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + ChangedParamCustomResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*ChangedParamCustomResponse::GetClassData() const { return &_class_data_; } + + +void ChangedParamCustomResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.param_server.ChangedParamCustomResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_param()->::mavsdk::rpc::param_server::CustomParam::MergeFrom( + from._internal_param()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void ChangedParamCustomResponse::CopyFrom(const ChangedParamCustomResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.ChangedParamCustomResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ChangedParamCustomResponse::IsInitialized() const { + return true; +} + +void ChangedParamCustomResponse::InternalSwap(ChangedParamCustomResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.param_, other->_impl_.param_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata ChangedParamCustomResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[19]); +} +// =================================================================== + +class IntParam::_Internal { + public: +}; + +IntParam::IntParam(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.IntParam) +} +IntParam::IntParam(const IntParam& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + IntParam* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.name_) {} + + , decltype(_impl_.value_) {} + + , /*decltype(_impl_._cached_size_)*/{}}; + + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + _impl_.name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (!from._internal_name().empty()) { + _this->_impl_.name_.Set(from._internal_name(), _this->GetArenaForAllocation()); + } + _this->_impl_.value_ = from._impl_.value_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.IntParam) +} + +inline void IntParam::SharedCtor(::_pb::Arena* arena) { + (void)arena; + new (&_impl_) Impl_{ + decltype(_impl_.name_) {} + + , decltype(_impl_.value_) { 0 } + + , /*decltype(_impl_._cached_size_)*/{} + }; + _impl_.name_.InitDefault(); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + _impl_.name_.Set("", GetArenaForAllocation()); + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING +} + +IntParam::~IntParam() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.IntParam) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void IntParam::SharedDtor() { + ABSL_DCHECK(GetArenaForAllocation() == nullptr); + _impl_.name_.Destroy(); +} + +void IntParam::SetCachedSize(int size) const { + _impl_._cached_size_.Set(size); +} + +void IntParam::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.IntParam) + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.name_.ClearToEmpty(); + _impl_.value_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* IntParam::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + ::uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // string name = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 10)) { + auto str = _internal_mutable_name(); + ptr = ::_pbi::InlineGreedyStringParser(str, ptr, ctx); + CHK_(ptr); + CHK_(::_pbi::VerifyUTF8(str, "mavsdk.rpc.param_server.IntParam.name")); + } else { + goto handle_unusual; + } + continue; + // int32 value = 2; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast<::uint8_t>(tag) == 16)) { + _impl_.value_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else { + goto handle_unusual; + } + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +::uint8_t* IntParam::_InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.IntParam) + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // string name = 1; + if (!this->_internal_name().empty()) { + const std::string& _s = this->_internal_name(); + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.param_server.IntParam.name"); + target = stream->WriteStringMaybeAliased(1, _s, target); + } + + // int32 value = 2; + if (this->_internal_value() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteInt32ToArray( + 2, this->_internal_value(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::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.param_server.IntParam) + return target; +} + +::size_t IntParam::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.IntParam) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // string name = 1; + if (!this->_internal_name().empty()) { + total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_name()); + } + + // int32 value = 2; + if (this->_internal_value() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_value()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData IntParam::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSourceCheck, + IntParam::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*IntParam::GetClassData() const { return &_class_data_; } + + +void IntParam::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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.param_server.IntParam) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (!from._internal_name().empty()) { + _this->_internal_set_name(from._internal_name()); + } + if (from._internal_value() != 0) { + _this->_internal_set_value(from._internal_value()); + } + _this->_internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void IntParam::CopyFrom(const IntParam& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.IntParam) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool IntParam::IsInitialized() const { + return true; +} + +void IntParam::InternalSwap(IntParam* other) { + using std::swap; + auto* lhs_arena = GetArenaForAllocation(); + auto* rhs_arena = other->GetArenaForAllocation(); + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.name_, lhs_arena, + &other->_impl_.name_, rhs_arena); + + swap(_impl_.value_, other->_impl_.value_); +} + +::PROTOBUF_NAMESPACE_ID::Metadata IntParam::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[20]); +} +// =================================================================== + +class FloatParam::_Internal { + public: +}; + +FloatParam::FloatParam(::PROTOBUF_NAMESPACE_ID::Arena* arena) + : ::PROTOBUF_NAMESPACE_ID::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.FloatParam) +} +FloatParam::FloatParam(const FloatParam& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + FloatParam* const _this = this; (void)_this; + new (&_impl_) Impl_{ + decltype(_impl_.name_) {} , decltype(_impl_.value_) {} @@ -4136,7 +5038,7 @@ void FloatParam::InternalSwap(FloatParam* other) { ::PROTOBUF_NAMESPACE_ID::Metadata FloatParam::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[15]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[21]); } // =================================================================== @@ -4379,7 +5281,7 @@ void CustomParam::InternalSwap(CustomParam* other) { ::PROTOBUF_NAMESPACE_ID::Metadata CustomParam::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[16]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[22]); } // =================================================================== @@ -4631,7 +5533,7 @@ void AllParams::InternalSwap(AllParams* other) { ::PROTOBUF_NAMESPACE_ID::Metadata AllParams::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[17]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[23]); } // =================================================================== @@ -4860,7 +5762,7 @@ void ParamServerResult::InternalSwap(ParamServerResult* other) { ::PROTOBUF_NAMESPACE_ID::Metadata ParamServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[18]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[24]); } // @@protoc_insertion_point(namespace_scope) } // namespace param_server @@ -4923,6 +5825,30 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::RetrieveAllParamsRespo Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::ChangedParamIntResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::ChangedParamIntResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::ChangedParamIntResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::ChangedParamFloatResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::ChangedParamFloatResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::ChangedParamFloatResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::ChangedParamCustomResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::ChangedParamCustomResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::ChangedParamCustomResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::param_server::IntParam* Arena::CreateMaybeMessage< ::mavsdk::rpc::param_server::IntParam >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::param_server::IntParam >(arena); diff --git a/src/mavsdk_server/src/generated/param_server/param_server.pb.h b/src/mavsdk_server/src/generated/param_server/param_server.pb.h index 258c210955..702e782d3d 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.pb.h +++ b/src/mavsdk_server/src/generated/param_server/param_server.pb.h @@ -59,6 +59,15 @@ namespace param_server { class AllParams; struct AllParamsDefaultTypeInternal; extern AllParamsDefaultTypeInternal _AllParams_default_instance_; +class ChangedParamCustomResponse; +struct ChangedParamCustomResponseDefaultTypeInternal; +extern ChangedParamCustomResponseDefaultTypeInternal _ChangedParamCustomResponse_default_instance_; +class ChangedParamFloatResponse; +struct ChangedParamFloatResponseDefaultTypeInternal; +extern ChangedParamFloatResponseDefaultTypeInternal _ChangedParamFloatResponse_default_instance_; +class ChangedParamIntResponse; +struct ChangedParamIntResponseDefaultTypeInternal; +extern ChangedParamIntResponseDefaultTypeInternal _ChangedParamIntResponse_default_instance_; class CustomParam; struct CustomParamDefaultTypeInternal; extern CustomParamDefaultTypeInternal _CustomParam_default_instance_; @@ -113,6 +122,15 @@ extern RetrieveParamIntRequestDefaultTypeInternal _RetrieveParamIntRequest_defau class RetrieveParamIntResponse; struct RetrieveParamIntResponseDefaultTypeInternal; extern RetrieveParamIntResponseDefaultTypeInternal _RetrieveParamIntResponse_default_instance_; +class SubscribeChangedParamCustomRequest; +struct SubscribeChangedParamCustomRequestDefaultTypeInternal; +extern SubscribeChangedParamCustomRequestDefaultTypeInternal _SubscribeChangedParamCustomRequest_default_instance_; +class SubscribeChangedParamFloatRequest; +struct SubscribeChangedParamFloatRequestDefaultTypeInternal; +extern SubscribeChangedParamFloatRequestDefaultTypeInternal _SubscribeChangedParamFloatRequest_default_instance_; +class SubscribeChangedParamIntRequest; +struct SubscribeChangedParamIntRequestDefaultTypeInternal; +extern SubscribeChangedParamIntRequestDefaultTypeInternal _SubscribeChangedParamIntRequest_default_instance_; } // namespace param_server } // namespace rpc } // namespace mavsdk @@ -120,6 +138,12 @@ PROTOBUF_NAMESPACE_OPEN template <> ::mavsdk::rpc::param_server::AllParams* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::AllParams>(Arena*); template <> +::mavsdk::rpc::param_server::ChangedParamCustomResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::ChangedParamCustomResponse>(Arena*); +template <> +::mavsdk::rpc::param_server::ChangedParamFloatResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::ChangedParamFloatResponse>(Arena*); +template <> +::mavsdk::rpc::param_server::ChangedParamIntResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::ChangedParamIntResponse>(Arena*); +template <> ::mavsdk::rpc::param_server::CustomParam* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::CustomParam>(Arena*); template <> ::mavsdk::rpc::param_server::FloatParam* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::FloatParam>(Arena*); @@ -155,6 +179,12 @@ template <> ::mavsdk::rpc::param_server::RetrieveParamIntRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::RetrieveParamIntRequest>(Arena*); template <> ::mavsdk::rpc::param_server::RetrieveParamIntResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::RetrieveParamIntResponse>(Arena*); +template <> +::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest>(Arena*); +template <> +::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest>(Arena*); +template <> +::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest>(Arena*); PROTOBUF_NAMESPACE_CLOSE namespace mavsdk { @@ -2529,25 +2559,24 @@ class RetrieveAllParamsResponse final : friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- -class IntParam final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.IntParam) */ { +class SubscribeChangedParamIntRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.SubscribeChangedParamIntRequest) */ { public: - inline IntParam() : IntParam(nullptr) {} - ~IntParam() override; + inline SubscribeChangedParamIntRequest() : SubscribeChangedParamIntRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR IntParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeChangedParamIntRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - IntParam(const IntParam& from); - IntParam(IntParam&& from) noexcept - : IntParam() { + SubscribeChangedParamIntRequest(const SubscribeChangedParamIntRequest& from); + SubscribeChangedParamIntRequest(SubscribeChangedParamIntRequest&& from) noexcept + : SubscribeChangedParamIntRequest() { *this = ::std::move(from); } - inline IntParam& operator=(const IntParam& from) { + inline SubscribeChangedParamIntRequest& operator=(const SubscribeChangedParamIntRequest& from) { CopyFrom(from); return *this; } - inline IntParam& operator=(IntParam&& from) noexcept { + inline SubscribeChangedParamIntRequest& operator=(SubscribeChangedParamIntRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2577,20 +2606,20 @@ class IntParam final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const IntParam& default_instance() { + static const SubscribeChangedParamIntRequest& default_instance() { return *internal_default_instance(); } - static inline const IntParam* internal_default_instance() { - return reinterpret_cast( - &_IntParam_default_instance_); + static inline const SubscribeChangedParamIntRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeChangedParamIntRequest_default_instance_); } static constexpr int kIndexInFileMessages = 14; - friend void swap(IntParam& a, IntParam& b) { + friend void swap(SubscribeChangedParamIntRequest& a, SubscribeChangedParamIntRequest& b) { a.Swap(&b); } - inline void Swap(IntParam* other) { + inline void Swap(SubscribeChangedParamIntRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2603,7 +2632,7 @@ class IntParam final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(IntParam* other) { + void UnsafeArenaSwap(SubscribeChangedParamIntRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2611,40 +2640,26 @@ class IntParam final : // implements Message ---------------------------------------------- - IntParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeChangedParamIntRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const IntParam& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const IntParam& from) { - IntParam::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeChangedParamIntRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeChangedParamIntRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(IntParam* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.param_server.IntParam"; + return "mavsdk.rpc.param_server.SubscribeChangedParamIntRequest"; } protected: - explicit IntParam(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeChangedParamIntRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2656,41 +2671,7 @@ class IntParam final : // accessors ------------------------------------------------------- - enum : int { - kNameFieldNumber = 1, - kValueFieldNumber = 2, - }; - // string name = 1; - void clear_name() ; - const std::string& name() const; - - - - - template - void set_name(Arg_&& arg, Args_... args); - std::string* mutable_name(); - PROTOBUF_NODISCARD std::string* release_name(); - void set_allocated_name(std::string* ptr); - - private: - const std::string& _internal_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( - const std::string& value); - std::string* _internal_mutable_name(); - - public: - // int32 value = 2; - void clear_value() ; - ::int32_t value() const; - void set_value(::int32_t value); - - private: - ::int32_t _internal_value() const; - void _internal_set_value(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.IntParam) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.SubscribeChangedParamIntRequest) private: class _Internal; @@ -2698,33 +2679,29 @@ class IntParam final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; - ::int32_t value_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- -class FloatParam final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.FloatParam) */ { +class ChangedParamIntResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.ChangedParamIntResponse) */ { public: - inline FloatParam() : FloatParam(nullptr) {} - ~FloatParam() override; + inline ChangedParamIntResponse() : ChangedParamIntResponse(nullptr) {} + ~ChangedParamIntResponse() override; template - explicit PROTOBUF_CONSTEXPR FloatParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ChangedParamIntResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - FloatParam(const FloatParam& from); - FloatParam(FloatParam&& from) noexcept - : FloatParam() { + ChangedParamIntResponse(const ChangedParamIntResponse& from); + ChangedParamIntResponse(ChangedParamIntResponse&& from) noexcept + : ChangedParamIntResponse() { *this = ::std::move(from); } - inline FloatParam& operator=(const FloatParam& from) { + inline ChangedParamIntResponse& operator=(const ChangedParamIntResponse& from) { CopyFrom(from); return *this; } - inline FloatParam& operator=(FloatParam&& from) noexcept { + inline ChangedParamIntResponse& operator=(ChangedParamIntResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2754,20 +2731,20 @@ class FloatParam final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FloatParam& default_instance() { + static const ChangedParamIntResponse& default_instance() { return *internal_default_instance(); } - static inline const FloatParam* internal_default_instance() { - return reinterpret_cast( - &_FloatParam_default_instance_); + static inline const ChangedParamIntResponse* internal_default_instance() { + return reinterpret_cast( + &_ChangedParamIntResponse_default_instance_); } static constexpr int kIndexInFileMessages = 15; - friend void swap(FloatParam& a, FloatParam& b) { + friend void swap(ChangedParamIntResponse& a, ChangedParamIntResponse& b) { a.Swap(&b); } - inline void Swap(FloatParam* other) { + inline void Swap(ChangedParamIntResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2780,7 +2757,7 @@ class FloatParam final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FloatParam* other) { + void UnsafeArenaSwap(ChangedParamIntResponse* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2788,14 +2765,14 @@ class FloatParam final : // implements Message ---------------------------------------------- - FloatParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ChangedParamIntResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const FloatParam& from); + void CopyFrom(const ChangedParamIntResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const FloatParam& from) { - FloatParam::MergeImpl(*this, from); + void MergeFrom( const ChangedParamIntResponse& from) { + ChangedParamIntResponse::MergeImpl(*this, from); } private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::Message& from_msg); @@ -2813,15 +2790,15 @@ class FloatParam final : void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(FloatParam* other); + void InternalSwap(ChangedParamIntResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.param_server.FloatParam"; + return "mavsdk.rpc.param_server.ChangedParamIntResponse"; } protected: - explicit FloatParam(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit ChangedParamIntResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -2834,40 +2811,23 @@ class FloatParam final : // accessors ------------------------------------------------------- enum : int { - kNameFieldNumber = 1, - kValueFieldNumber = 2, + kParamFieldNumber = 1, }; - // string name = 1; - void clear_name() ; - const std::string& name() const; - - - - - template - void set_name(Arg_&& arg, Args_... args); - std::string* mutable_name(); - PROTOBUF_NODISCARD std::string* release_name(); - void set_allocated_name(std::string* ptr); - - private: - const std::string& _internal_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( - const std::string& value); - std::string* _internal_mutable_name(); - - public: - // float value = 2; - void clear_value() ; - float value() const; - void set_value(float value); - + // .mavsdk.rpc.param_server.IntParam param = 1; + bool has_param() const; + void clear_param() ; + const ::mavsdk::rpc::param_server::IntParam& param() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::param_server::IntParam* release_param(); + ::mavsdk::rpc::param_server::IntParam* mutable_param(); + void set_allocated_param(::mavsdk::rpc::param_server::IntParam* param); private: - float _internal_value() const; - void _internal_set_value(float value); - + const ::mavsdk::rpc::param_server::IntParam& _internal_param() const; + ::mavsdk::rpc::param_server::IntParam* _internal_mutable_param(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.FloatParam) + void unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::IntParam* param); + ::mavsdk::rpc::param_server::IntParam* unsafe_arena_release_param(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.ChangedParamIntResponse) private: class _Internal; @@ -2875,33 +2835,32 @@ class FloatParam final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; - float value_; + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::param_server::IntParam* param_; }; union { Impl_ _impl_; }; friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- -class CustomParam final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.CustomParam) */ { +class SubscribeChangedParamFloatRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest) */ { public: - inline CustomParam() : CustomParam(nullptr) {} - ~CustomParam() override; + inline SubscribeChangedParamFloatRequest() : SubscribeChangedParamFloatRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR CustomParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeChangedParamFloatRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - CustomParam(const CustomParam& from); - CustomParam(CustomParam&& from) noexcept - : CustomParam() { + SubscribeChangedParamFloatRequest(const SubscribeChangedParamFloatRequest& from); + SubscribeChangedParamFloatRequest(SubscribeChangedParamFloatRequest&& from) noexcept + : SubscribeChangedParamFloatRequest() { *this = ::std::move(from); } - inline CustomParam& operator=(const CustomParam& from) { + inline SubscribeChangedParamFloatRequest& operator=(const SubscribeChangedParamFloatRequest& from) { CopyFrom(from); return *this; } - inline CustomParam& operator=(CustomParam&& from) noexcept { + inline SubscribeChangedParamFloatRequest& operator=(SubscribeChangedParamFloatRequest&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2931,20 +2890,20 @@ class CustomParam final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CustomParam& default_instance() { + static const SubscribeChangedParamFloatRequest& default_instance() { return *internal_default_instance(); } - static inline const CustomParam* internal_default_instance() { - return reinterpret_cast( - &_CustomParam_default_instance_); + static inline const SubscribeChangedParamFloatRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeChangedParamFloatRequest_default_instance_); } static constexpr int kIndexInFileMessages = 16; - friend void swap(CustomParam& a, CustomParam& b) { + friend void swap(SubscribeChangedParamFloatRequest& a, SubscribeChangedParamFloatRequest& b) { a.Swap(&b); } - inline void Swap(CustomParam* other) { + inline void Swap(SubscribeChangedParamFloatRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -2957,7 +2916,7 @@ class CustomParam final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CustomParam* other) { + void UnsafeArenaSwap(SubscribeChangedParamFloatRequest* other) { if (other == this) return; ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -2965,40 +2924,26 @@ class CustomParam final : // implements Message ---------------------------------------------- - CustomParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeChangedParamFloatRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const CustomParam& from); - using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom( const CustomParam& from) { - CustomParam::MergeImpl(*this, from); + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeChangedParamFloatRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeChangedParamFloatRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); } - private: - static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; - ::uint8_t* _InternalSerialize( - ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; - int GetCachedSize() const final { return _impl_._cached_size_.Get(); } - - private: - void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); - void SharedDtor(); - void SetCachedSize(int size) const final; - void InternalSwap(CustomParam* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.param_server.CustomParam"; + return "mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest"; } protected: - explicit CustomParam(::PROTOBUF_NAMESPACE_ID::Arena* arena); + explicit SubscribeChangedParamFloatRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); public: static const ClassData _class_data_; @@ -3010,51 +2955,7 @@ class CustomParam final : // accessors ------------------------------------------------------- - enum : int { - kNameFieldNumber = 1, - kValueFieldNumber = 2, - }; - // string name = 1; - void clear_name() ; - const std::string& name() const; - - - - - template - void set_name(Arg_&& arg, Args_... args); - std::string* mutable_name(); - PROTOBUF_NODISCARD std::string* release_name(); - void set_allocated_name(std::string* ptr); - - private: - const std::string& _internal_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( - const std::string& value); - std::string* _internal_mutable_name(); - - public: - // string value = 2; - void clear_value() ; - const std::string& value() const; - - - - - template - void set_value(Arg_&& arg, Args_... args); - std::string* mutable_value(); - PROTOBUF_NODISCARD std::string* release_value(); - void set_allocated_value(std::string* ptr); - - private: - const std::string& _internal_value() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_value( - const std::string& value); - std::string* _internal_mutable_value(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.CustomParam) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.SubscribeChangedParamFloatRequest) private: class _Internal; @@ -3062,29 +2963,1010 @@ class CustomParam final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; struct Impl_ { - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; - ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr value_; - mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; }; - union { Impl_ _impl_; }; friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- -class AllParams final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.AllParams) */ { +class ChangedParamFloatResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.ChangedParamFloatResponse) */ { public: - inline AllParams() : AllParams(nullptr) {} - ~AllParams() override; + inline ChangedParamFloatResponse() : ChangedParamFloatResponse(nullptr) {} + ~ChangedParamFloatResponse() override; template - explicit PROTOBUF_CONSTEXPR AllParams(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ChangedParamFloatResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - AllParams(const AllParams& from); - AllParams(AllParams&& from) noexcept - : AllParams() { + ChangedParamFloatResponse(const ChangedParamFloatResponse& from); + ChangedParamFloatResponse(ChangedParamFloatResponse&& from) noexcept + : ChangedParamFloatResponse() { *this = ::std::move(from); } - inline AllParams& operator=(const AllParams& from) { + inline ChangedParamFloatResponse& operator=(const ChangedParamFloatResponse& from) { + CopyFrom(from); + return *this; + } + inline ChangedParamFloatResponse& operator=(ChangedParamFloatResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 ChangedParamFloatResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ChangedParamFloatResponse* internal_default_instance() { + return reinterpret_cast( + &_ChangedParamFloatResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 17; + + friend void swap(ChangedParamFloatResponse& a, ChangedParamFloatResponse& b) { + a.Swap(&b); + } + inline void Swap(ChangedParamFloatResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ChangedParamFloatResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ChangedParamFloatResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ChangedParamFloatResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const ChangedParamFloatResponse& from) { + ChangedParamFloatResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ChangedParamFloatResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.ChangedParamFloatResponse"; + } + protected: + explicit ChangedParamFloatResponse(::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 { + kParamFieldNumber = 1, + }; + // .mavsdk.rpc.param_server.FloatParam param = 1; + bool has_param() const; + void clear_param() ; + const ::mavsdk::rpc::param_server::FloatParam& param() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::param_server::FloatParam* release_param(); + ::mavsdk::rpc::param_server::FloatParam* mutable_param(); + void set_allocated_param(::mavsdk::rpc::param_server::FloatParam* param); + private: + const ::mavsdk::rpc::param_server::FloatParam& _internal_param() const; + ::mavsdk::rpc::param_server::FloatParam* _internal_mutable_param(); + public: + void unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::FloatParam* param); + ::mavsdk::rpc::param_server::FloatParam* unsafe_arena_release_param(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.ChangedParamFloatResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::param_server::FloatParam* param_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeChangedParamCustomRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest) */ { + public: + inline SubscribeChangedParamCustomRequest() : SubscribeChangedParamCustomRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeChangedParamCustomRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeChangedParamCustomRequest(const SubscribeChangedParamCustomRequest& from); + SubscribeChangedParamCustomRequest(SubscribeChangedParamCustomRequest&& from) noexcept + : SubscribeChangedParamCustomRequest() { + *this = ::std::move(from); + } + + inline SubscribeChangedParamCustomRequest& operator=(const SubscribeChangedParamCustomRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeChangedParamCustomRequest& operator=(SubscribeChangedParamCustomRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 SubscribeChangedParamCustomRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeChangedParamCustomRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeChangedParamCustomRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 18; + + friend void swap(SubscribeChangedParamCustomRequest& a, SubscribeChangedParamCustomRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeChangedParamCustomRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeChangedParamCustomRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeChangedParamCustomRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeChangedParamCustomRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeChangedParamCustomRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest"; + } + protected: + explicit SubscribeChangedParamCustomRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.SubscribeChangedParamCustomRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class ChangedParamCustomResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.ChangedParamCustomResponse) */ { + public: + inline ChangedParamCustomResponse() : ChangedParamCustomResponse(nullptr) {} + ~ChangedParamCustomResponse() override; + template + explicit PROTOBUF_CONSTEXPR ChangedParamCustomResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + ChangedParamCustomResponse(const ChangedParamCustomResponse& from); + ChangedParamCustomResponse(ChangedParamCustomResponse&& from) noexcept + : ChangedParamCustomResponse() { + *this = ::std::move(from); + } + + inline ChangedParamCustomResponse& operator=(const ChangedParamCustomResponse& from) { + CopyFrom(from); + return *this; + } + inline ChangedParamCustomResponse& operator=(ChangedParamCustomResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 ChangedParamCustomResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ChangedParamCustomResponse* internal_default_instance() { + return reinterpret_cast( + &_ChangedParamCustomResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 19; + + friend void swap(ChangedParamCustomResponse& a, ChangedParamCustomResponse& b) { + a.Swap(&b); + } + inline void Swap(ChangedParamCustomResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ChangedParamCustomResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ChangedParamCustomResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const ChangedParamCustomResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const ChangedParamCustomResponse& from) { + ChangedParamCustomResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ChangedParamCustomResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.ChangedParamCustomResponse"; + } + protected: + explicit ChangedParamCustomResponse(::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 { + kParamFieldNumber = 1, + }; + // .mavsdk.rpc.param_server.CustomParam param = 1; + bool has_param() const; + void clear_param() ; + const ::mavsdk::rpc::param_server::CustomParam& param() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::param_server::CustomParam* release_param(); + ::mavsdk::rpc::param_server::CustomParam* mutable_param(); + void set_allocated_param(::mavsdk::rpc::param_server::CustomParam* param); + private: + const ::mavsdk::rpc::param_server::CustomParam& _internal_param() const; + ::mavsdk::rpc::param_server::CustomParam* _internal_mutable_param(); + public: + void unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::CustomParam* param); + ::mavsdk::rpc::param_server::CustomParam* unsafe_arena_release_param(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.ChangedParamCustomResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::HasBits<1> _has_bits_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + ::mavsdk::rpc::param_server::CustomParam* param_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class IntParam final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.IntParam) */ { + public: + inline IntParam() : IntParam(nullptr) {} + ~IntParam() override; + template + explicit PROTOBUF_CONSTEXPR IntParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + IntParam(const IntParam& from); + IntParam(IntParam&& from) noexcept + : IntParam() { + *this = ::std::move(from); + } + + inline IntParam& operator=(const IntParam& from) { + CopyFrom(from); + return *this; + } + inline IntParam& operator=(IntParam&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 IntParam& default_instance() { + return *internal_default_instance(); + } + static inline const IntParam* internal_default_instance() { + return reinterpret_cast( + &_IntParam_default_instance_); + } + static constexpr int kIndexInFileMessages = + 20; + + friend void swap(IntParam& a, IntParam& b) { + a.Swap(&b); + } + inline void Swap(IntParam* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(IntParam* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + IntParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const IntParam& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const IntParam& from) { + IntParam::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(IntParam* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.IntParam"; + } + protected: + explicit IntParam(::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 { + kNameFieldNumber = 1, + kValueFieldNumber = 2, + }; + // string name = 1; + void clear_name() ; + const std::string& name() const; + + + + + template + void set_name(Arg_&& arg, Args_... args); + std::string* mutable_name(); + PROTOBUF_NODISCARD std::string* release_name(); + void set_allocated_name(std::string* ptr); + + private: + const std::string& _internal_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( + const std::string& value); + std::string* _internal_mutable_name(); + + public: + // int32 value = 2; + void clear_value() ; + ::int32_t value() const; + void set_value(::int32_t value); + + private: + ::int32_t _internal_value() const; + void _internal_set_value(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.IntParam) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; + ::int32_t value_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class FloatParam final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.FloatParam) */ { + public: + inline FloatParam() : FloatParam(nullptr) {} + ~FloatParam() override; + template + explicit PROTOBUF_CONSTEXPR FloatParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + FloatParam(const FloatParam& from); + FloatParam(FloatParam&& from) noexcept + : FloatParam() { + *this = ::std::move(from); + } + + inline FloatParam& operator=(const FloatParam& from) { + CopyFrom(from); + return *this; + } + inline FloatParam& operator=(FloatParam&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 FloatParam& default_instance() { + return *internal_default_instance(); + } + static inline const FloatParam* internal_default_instance() { + return reinterpret_cast( + &_FloatParam_default_instance_); + } + static constexpr int kIndexInFileMessages = + 21; + + friend void swap(FloatParam& a, FloatParam& b) { + a.Swap(&b); + } + inline void Swap(FloatParam* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(FloatParam* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + FloatParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const FloatParam& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const FloatParam& from) { + FloatParam::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(FloatParam* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.FloatParam"; + } + protected: + explicit FloatParam(::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 { + kNameFieldNumber = 1, + kValueFieldNumber = 2, + }; + // string name = 1; + void clear_name() ; + const std::string& name() const; + + + + + template + void set_name(Arg_&& arg, Args_... args); + std::string* mutable_name(); + PROTOBUF_NODISCARD std::string* release_name(); + void set_allocated_name(std::string* ptr); + + private: + const std::string& _internal_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( + const std::string& value); + std::string* _internal_mutable_name(); + + public: + // float value = 2; + void clear_value() ; + float value() const; + void set_value(float value); + + private: + float _internal_value() const; + void _internal_set_value(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.FloatParam) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; + float value_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class CustomParam final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.CustomParam) */ { + public: + inline CustomParam() : CustomParam(nullptr) {} + ~CustomParam() override; + template + explicit PROTOBUF_CONSTEXPR CustomParam(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + CustomParam(const CustomParam& from); + CustomParam(CustomParam&& from) noexcept + : CustomParam() { + *this = ::std::move(from); + } + + inline CustomParam& operator=(const CustomParam& from) { + CopyFrom(from); + return *this; + } + inline CustomParam& operator=(CustomParam&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance); + } + inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); + } + + 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 CustomParam& default_instance() { + return *internal_default_instance(); + } + static inline const CustomParam* internal_default_instance() { + return reinterpret_cast( + &_CustomParam_default_instance_); + } + static constexpr int kIndexInFileMessages = + 22; + + friend void swap(CustomParam& a, CustomParam& b) { + a.Swap(&b); + } + inline void Swap(CustomParam* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(CustomParam* other) { + if (other == this) return; + ABSL_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + CustomParam* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const CustomParam& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom( const CustomParam& from) { + CustomParam::MergeImpl(*this, from); + } + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message& to_msg, const ::PROTOBUF_NAMESPACE_ID::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, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::PROTOBUF_NAMESPACE_ID::Arena* arena); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CustomParam* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.CustomParam"; + } + protected: + explicit CustomParam(::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 { + kNameFieldNumber = 1, + kValueFieldNumber = 2, + }; + // string name = 1; + void clear_name() ; + const std::string& name() const; + + + + + template + void set_name(Arg_&& arg, Args_... args); + std::string* mutable_name(); + PROTOBUF_NODISCARD std::string* release_name(); + void set_allocated_name(std::string* ptr); + + private: + const std::string& _internal_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_name( + const std::string& value); + std::string* _internal_mutable_name(); + + public: + // string value = 2; + void clear_value() ; + const std::string& value() const; + + + + + template + void set_value(Arg_&& arg, Args_... args); + std::string* mutable_value(); + PROTOBUF_NODISCARD std::string* release_value(); + void set_allocated_value(std::string* ptr); + + private: + const std::string& _internal_value() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_value( + const std::string& value); + std::string* _internal_mutable_value(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.CustomParam) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + struct Impl_ { + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr value_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + +class AllParams final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.AllParams) */ { + public: + inline AllParams() : AllParams(nullptr) {} + ~AllParams() override; + template + explicit PROTOBUF_CONSTEXPR AllParams(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + AllParams(const AllParams& from); + AllParams(AllParams&& from) noexcept + : AllParams() { + *this = ::std::move(from); + } + + inline AllParams& operator=(const AllParams& from) { CopyFrom(from); return *this; } @@ -3126,7 +4008,7 @@ class AllParams final : &_AllParams_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 23; friend void swap(AllParams& a, AllParams& b) { a.Swap(&b); @@ -3335,7 +4217,7 @@ class ParamServerResult final : &_ParamServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 24; friend void swap(ParamServerResult& a, ParamServerResult& b) { a.Swap(&b); @@ -4616,6 +5498,291 @@ inline void RetrieveAllParamsResponse::set_allocated_params(::mavsdk::rpc::param // ------------------------------------------------------------------- +// SubscribeChangedParamIntRequest + +// ------------------------------------------------------------------- + +// ChangedParamIntResponse + +// .mavsdk.rpc.param_server.IntParam param = 1; +inline bool ChangedParamIntResponse::has_param() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.param_ != nullptr); + return value; +} +inline void ChangedParamIntResponse::clear_param() { + if (_impl_.param_ != nullptr) _impl_.param_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::param_server::IntParam& ChangedParamIntResponse::_internal_param() const { + const ::mavsdk::rpc::param_server::IntParam* p = _impl_.param_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::param_server::_IntParam_default_instance_); +} +inline const ::mavsdk::rpc::param_server::IntParam& ChangedParamIntResponse::param() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.param_server.ChangedParamIntResponse.param) + return _internal_param(); +} +inline void ChangedParamIntResponse::unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::IntParam* param) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.param_); + } + _impl_.param_ = param; + if (param) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.param_server.ChangedParamIntResponse.param) +} +inline ::mavsdk::rpc::param_server::IntParam* ChangedParamIntResponse::release_param() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::IntParam* temp = _impl_.param_; + _impl_.param_ = 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::param_server::IntParam* ChangedParamIntResponse::unsafe_arena_release_param() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.param_server.ChangedParamIntResponse.param) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::IntParam* temp = _impl_.param_; + _impl_.param_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::param_server::IntParam* ChangedParamIntResponse::_internal_mutable_param() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.param_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::param_server::IntParam>(GetArenaForAllocation()); + _impl_.param_ = p; + } + return _impl_.param_; +} +inline ::mavsdk::rpc::param_server::IntParam* ChangedParamIntResponse::mutable_param() { + ::mavsdk::rpc::param_server::IntParam* _msg = _internal_mutable_param(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.param_server.ChangedParamIntResponse.param) + return _msg; +} +inline void ChangedParamIntResponse::set_allocated_param(::mavsdk::rpc::param_server::IntParam* param) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.param_; + } + if (param) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(param); + if (message_arena != submessage_arena) { + param = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, param, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.param_ = param; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.param_server.ChangedParamIntResponse.param) +} + +// ------------------------------------------------------------------- + +// SubscribeChangedParamFloatRequest + +// ------------------------------------------------------------------- + +// ChangedParamFloatResponse + +// .mavsdk.rpc.param_server.FloatParam param = 1; +inline bool ChangedParamFloatResponse::has_param() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.param_ != nullptr); + return value; +} +inline void ChangedParamFloatResponse::clear_param() { + if (_impl_.param_ != nullptr) _impl_.param_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::param_server::FloatParam& ChangedParamFloatResponse::_internal_param() const { + const ::mavsdk::rpc::param_server::FloatParam* p = _impl_.param_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::param_server::_FloatParam_default_instance_); +} +inline const ::mavsdk::rpc::param_server::FloatParam& ChangedParamFloatResponse::param() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.param_server.ChangedParamFloatResponse.param) + return _internal_param(); +} +inline void ChangedParamFloatResponse::unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::FloatParam* param) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.param_); + } + _impl_.param_ = param; + if (param) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.param_server.ChangedParamFloatResponse.param) +} +inline ::mavsdk::rpc::param_server::FloatParam* ChangedParamFloatResponse::release_param() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::FloatParam* temp = _impl_.param_; + _impl_.param_ = 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::param_server::FloatParam* ChangedParamFloatResponse::unsafe_arena_release_param() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.param_server.ChangedParamFloatResponse.param) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::FloatParam* temp = _impl_.param_; + _impl_.param_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::param_server::FloatParam* ChangedParamFloatResponse::_internal_mutable_param() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.param_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::param_server::FloatParam>(GetArenaForAllocation()); + _impl_.param_ = p; + } + return _impl_.param_; +} +inline ::mavsdk::rpc::param_server::FloatParam* ChangedParamFloatResponse::mutable_param() { + ::mavsdk::rpc::param_server::FloatParam* _msg = _internal_mutable_param(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.param_server.ChangedParamFloatResponse.param) + return _msg; +} +inline void ChangedParamFloatResponse::set_allocated_param(::mavsdk::rpc::param_server::FloatParam* param) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.param_; + } + if (param) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(param); + if (message_arena != submessage_arena) { + param = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, param, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.param_ = param; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.param_server.ChangedParamFloatResponse.param) +} + +// ------------------------------------------------------------------- + +// SubscribeChangedParamCustomRequest + +// ------------------------------------------------------------------- + +// ChangedParamCustomResponse + +// .mavsdk.rpc.param_server.CustomParam param = 1; +inline bool ChangedParamCustomResponse::has_param() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.param_ != nullptr); + return value; +} +inline void ChangedParamCustomResponse::clear_param() { + if (_impl_.param_ != nullptr) _impl_.param_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::param_server::CustomParam& ChangedParamCustomResponse::_internal_param() const { + const ::mavsdk::rpc::param_server::CustomParam* p = _impl_.param_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::param_server::_CustomParam_default_instance_); +} +inline const ::mavsdk::rpc::param_server::CustomParam& ChangedParamCustomResponse::param() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.param_server.ChangedParamCustomResponse.param) + return _internal_param(); +} +inline void ChangedParamCustomResponse::unsafe_arena_set_allocated_param( + ::mavsdk::rpc::param_server::CustomParam* param) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(_impl_.param_); + } + _impl_.param_ = param; + if (param) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.param_server.ChangedParamCustomResponse.param) +} +inline ::mavsdk::rpc::param_server::CustomParam* ChangedParamCustomResponse::release_param() { + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::CustomParam* temp = _impl_.param_; + _impl_.param_ = 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::param_server::CustomParam* ChangedParamCustomResponse::unsafe_arena_release_param() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.param_server.ChangedParamCustomResponse.param) + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::CustomParam* temp = _impl_.param_; + _impl_.param_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::param_server::CustomParam* ChangedParamCustomResponse::_internal_mutable_param() { + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.param_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::param_server::CustomParam>(GetArenaForAllocation()); + _impl_.param_ = p; + } + return _impl_.param_; +} +inline ::mavsdk::rpc::param_server::CustomParam* ChangedParamCustomResponse::mutable_param() { + ::mavsdk::rpc::param_server::CustomParam* _msg = _internal_mutable_param(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.param_server.ChangedParamCustomResponse.param) + return _msg; +} +inline void ChangedParamCustomResponse::set_allocated_param(::mavsdk::rpc::param_server::CustomParam* param) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete _impl_.param_; + } + if (param) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(param); + if (message_arena != submessage_arena) { + param = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, param, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + _impl_.param_ = param; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.param_server.ChangedParamCustomResponse.param) +} + +// ------------------------------------------------------------------- + // IntParam // string name = 1; diff --git a/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h b/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h index b6459574eb..1474dd53bf 100644 --- a/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h @@ -416,6 +416,132 @@ class ParamServerServiceImpl final : public rpc::param_server::ParamServerServic return grpc::Status::OK; } + grpc::Status SubscribeChangedParamInt( + grpc::ServerContext* /* context */, + const mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::ParamServer::ChangedParamIntHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_changed_param_int( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::ParamServer::IntParam changed_param_int) { + rpc::param_server::ChangedParamIntResponse rpc_response; + + rpc_response.set_allocated_param( + translateToRpcIntParam(changed_param_int).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_changed_param_int(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeChangedParamFloat( + grpc::ServerContext* /* context */, + const mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::ParamServer::ChangedParamFloatHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_changed_param_float( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::ParamServer::FloatParam changed_param_float) { + rpc::param_server::ChangedParamFloatResponse rpc_response; + + rpc_response.set_allocated_param( + translateToRpcFloatParam(changed_param_float).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_changed_param_float(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeChangedParamCustom( + grpc::ServerContext* /* context */, + const mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::ParamServer::ChangedParamCustomHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_changed_param_custom( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::ParamServer::CustomParam changed_param_custom) { + rpc::param_server::ChangedParamCustomResponse rpc_response; + + rpc_response.set_allocated_param( + translateToRpcCustomParam(changed_param_custom).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_changed_param_custom(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + void stop() { _stopped.store(true); From 2b7be2a76b59955b96dfa7b4fb34c6ab18c755f2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 24 Dec 2023 11:21:25 +1300 Subject: [PATCH 19/25] examples: add missing include Signed-off-by: Julian Oes --- examples/camera_server/camera_client.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 243f9d20dd..6dda0fdc2e 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include #include From 1103cb807ea97a4bea48f16a5aac91817e4438ad Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 24 Dec 2023 11:24:08 +1300 Subject: [PATCH 20/25] camera: fix a few casts Signed-off-by: Julian Oes --- src/mavsdk/plugins/camera/camera_impl.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index df8dc0795e..be328068b4 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -418,7 +418,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming MavlinkCommandSender::CommandLong cmd_start_video_streaming{}; cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING; - cmd_start_video_streaming.params.maybe_param1 = stream_id; + cmd_start_video_streaming.params.maybe_param1 = static_cast(stream_id); cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; return cmd_start_video_streaming; @@ -429,7 +429,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming( MavlinkCommandSender::CommandLong cmd_stop_video_streaming{}; cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING; - cmd_stop_video_streaming.params.maybe_param1 = stream_id; + cmd_stop_video_streaming.params.maybe_param1 = static_cast(stream_id); cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; return cmd_stop_video_streaming; @@ -1977,7 +1977,7 @@ void CameraImpl::reset_settings_async(const Camera::ResultCallback callback) MavlinkCommandSender::CommandLong cmd_format{}; cmd_format.command = MAV_CMD_RESET_CAMERA_SETTINGS; - cmd_format.params.maybe_param1 = 1.0; // reset + cmd_format.params.maybe_param1 = 1.0f; // reset cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; _system_impl->send_command_async( From 9e70232c33191d5db3e54ea30630a6ab062ae051 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 24 Dec 2023 12:11:31 +1300 Subject: [PATCH 21/25] camera: remove non-sensical tests We ought to have a request. Signed-off-by: Julian Oes --- .../test/camera_service_impl_test.cpp | 41 ------------------- 1 file changed, 41 deletions(-) diff --git a/src/mavsdk_server/test/camera_service_impl_test.cpp b/src/mavsdk_server/test/camera_service_impl_test.cpp index 34ec00508e..ee65d19ce4 100644 --- a/src/mavsdk_server/test/camera_service_impl_test.cpp +++ b/src/mavsdk_server/test/camera_service_impl_test.cpp @@ -274,47 +274,6 @@ TEST_P(CameraServiceImplTest, stopVideoResultIsTranslatedCorrectly) EXPECT_EQ(GetParam().first, CameraResult::Result_Name(response.camera_result().result())); } -TEST_F(CameraServiceImplTest, stopVideoEvenWhenArgsAreNull) -{ - EXPECT_CALL(_camera, stop_video()).Times(1); - - _camera_service.StopVideo(nullptr, nullptr, nullptr); -} - -TEST_P(CameraServiceImplTest, startVideoStreamingResultIsTranslatedCorrectly) -{ - ON_CALL(_camera, start_video_streaming(1)).WillByDefault(Return(GetParam().second)); - mavsdk::rpc::camera::StartVideoStreamingResponse response; - - _camera_service.StartVideoStreaming(nullptr, nullptr, &response); - - EXPECT_EQ(GetParam().first, CameraResult::Result_Name(response.camera_result().result())); -} - -TEST_F(CameraServiceImplTest, startsVideoStreamingEvenWhenArgsAreNull) -{ - EXPECT_CALL(_camera, start_video_streaming(1)).Times(1); - - _camera_service.StartVideoStreaming(nullptr, nullptr, nullptr); -} - -TEST_P(CameraServiceImplTest, stopVideoStreamingResultIsTranslatedCorrectly) -{ - ON_CALL(_camera, stop_video_streaming(1)).WillByDefault(Return(GetParam().second)); - mavsdk::rpc::camera::StopVideoStreamingResponse response; - - _camera_service.StopVideoStreaming(nullptr, nullptr, &response); - - EXPECT_EQ(GetParam().first, CameraResult::Result_Name(response.camera_result().result())); -} - -TEST_F(CameraServiceImplTest, stopsVideoStreamingEvenWhenArgsAreNull) -{ - EXPECT_CALL(_camera, stop_video_streaming(1)).Times(1); - - _camera_service.StopVideoStreaming(nullptr, nullptr, nullptr); -} - TEST_F(CameraServiceImplTest, setModeDoesNotFailWithAllNullParams) { _camera_service.SetMode(nullptr, nullptr, nullptr); From e07d875030c665f7cccaf4731323e54cd4580f4b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 24 Dec 2023 21:56:33 +1300 Subject: [PATCH 22/25] integration_tests: fix after rebase Signed-off-by: Julian Oes --- src/integration_tests/camera_reset_settings.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/integration_tests/camera_reset_settings.cpp b/src/integration_tests/camera_reset_settings.cpp index bbf0fc4b67..5f602b540c 100644 --- a/src/integration_tests/camera_reset_settings.cpp +++ b/src/integration_tests/camera_reset_settings.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(CameraTest, ResetSettings) { - Mavsdk mavsdk; + Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_udp_connection(); ASSERT_EQ(ret, ConnectionResult::Success); From 7399fc76acb08bb0c824d3c03ce0e5499c9b525e Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 24 Dec 2023 22:49:23 +1300 Subject: [PATCH 23/25] third_party: update mavlink to latest master Signed-off-by: Julian Oes --- .../core/mavlink_mission_transfer_client.cpp | 15 ++++++++++----- .../core/mavlink_mission_transfer_client_test.cpp | 8 +++++--- .../core/mavlink_mission_transfer_server.cpp | 6 ++++-- .../core/mavlink_mission_transfer_server_test.cpp | 3 ++- .../mission_raw_server_impl.cpp | 6 +++++- third_party/mavlink/CMakeLists.txt | 6 ++++-- 6 files changed, 30 insertions(+), 14 deletions(-) diff --git a/src/mavsdk/core/mavlink_mission_transfer_client.cpp b/src/mavsdk/core/mavlink_mission_transfer_client.cpp index 56a8a5e060..b326586926 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_client.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_client.cpp @@ -275,7 +275,8 @@ void MavlinkMissionTransferClient::UploadWorkItem::send_count() _target_system_id, MAV_COMP_ID_AUTOPILOT1, _items.size(), - _type); + _type, + 0); return message; })) { _timeout_handler.remove(_cookie); @@ -303,7 +304,8 @@ void MavlinkMissionTransferClient::UploadWorkItem::send_cancel_and_finish() _target_system_id, MAV_COMP_ID_AUTOPILOT1, MAV_MISSION_OPERATION_CANCELLED, - _type); + _type, + 0); return message; })) { callback_and_reset(Result::ConnectionError); @@ -350,7 +352,8 @@ void MavlinkMissionTransferClient::UploadWorkItem::process_mission_request( request_message.sysid, request_message.compid, MAV_MISSION_UNSUPPORTED, - _type); + _type, + 0); return message; })) { _timeout_handler.remove(_cookie); @@ -670,7 +673,8 @@ void MavlinkMissionTransferClient::DownloadWorkItem::send_ack_and_finish() _target_system_id, MAV_COMP_ID_AUTOPILOT1, MAV_MISSION_ACCEPTED, - _type); + _type, + 0); return message; })) { callback_and_reset(Result::ConnectionError); @@ -693,7 +697,8 @@ void MavlinkMissionTransferClient::DownloadWorkItem::send_cancel_and_finish() _target_system_id, MAV_COMP_ID_AUTOPILOT1, MAV_MISSION_OPERATION_CANCELLED, - _type); + _type, + 0); return message; })) { callback_and_reset(Result::ConnectionError); diff --git a/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp b/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp index 6885a074eb..32840269c3 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp @@ -83,7 +83,8 @@ mavlink_message_t make_mission_count(unsigned count) target_address.system_id, target_address.component_id, count, - MAV_MISSION_TYPE_MISSION); + MAV_MISSION_TYPE_MISSION, + 0); return message; } @@ -419,7 +420,8 @@ mavlink_message_t make_mission_ack(uint8_t type, uint8_t result) target_address.system_id, target_address.component_id, result, - type); + type, + 0); return message; } @@ -1695,7 +1697,7 @@ mavlink_message_t make_mission_current(uint16_t seq) { mavlink_message_t message; mavlink_msg_mission_current_pack( - own_address.system_id, own_address.component_id, &message, seq, 0, 0, 0); + own_address.system_id, own_address.component_id, &message, seq, 0, 0, 0, 0, 0, 0); return message; } diff --git a/src/mavsdk/core/mavlink_mission_transfer_server.cpp b/src/mavsdk/core/mavlink_mission_transfer_server.cpp index d3830b887e..3d4e44f30b 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_server.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_server.cpp @@ -192,7 +192,8 @@ void MavlinkMissionTransferServer::ReceiveIncomingMission::send_ack_and_finish() _target_system_id, _target_component_id, MAV_MISSION_ACCEPTED, - _type); + _type, + 0); return message; })) { callback_and_reset(Result::ConnectionError); @@ -215,7 +216,8 @@ void MavlinkMissionTransferServer::ReceiveIncomingMission::send_cancel_and_finis _target_system_id, _target_component_id, MAV_MISSION_OPERATION_CANCELLED, - _type); + _type, + 0); return message; })) { callback_and_reset(Result::ConnectionError); diff --git a/src/mavsdk/core/mavlink_mission_transfer_server_test.cpp b/src/mavsdk/core/mavlink_mission_transfer_server_test.cpp index 80525a0eaa..00ecff31a1 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_server_test.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_server_test.cpp @@ -83,7 +83,8 @@ static mavlink_message_t make_mission_count(unsigned count) target_address.system_id, target_address.component_id, count, - MAV_MISSION_TYPE_MISSION); + MAV_MISSION_TYPE_MISSION, + 0); return message; } diff --git a/src/mavsdk/plugins/mission_raw_server/mission_raw_server_impl.cpp b/src/mavsdk/plugins/mission_raw_server/mission_raw_server_impl.cpp index 1e6e6e5df9..285e8164de 100644 --- a/src/mavsdk/plugins/mission_raw_server/mission_raw_server_impl.cpp +++ b/src/mavsdk/plugins/mission_raw_server/mission_raw_server_impl.cpp @@ -261,7 +261,8 @@ void MissionRawServerImpl::process_mission_clear(const mavlink_message_t message message.sysid, message.compid, MAV_MISSION_RESULT::MAV_MISSION_ACCEPTED, - clear_all.mission_type); + clear_all.mission_type, + 0); return response_message; }); } @@ -370,6 +371,9 @@ void MissionRawServerImpl::set_current_seq(std::size_t seq) static_cast(_current_seq), 0, 0, + 0, + 0, + 0, 0); return message; }); diff --git a/third_party/mavlink/CMakeLists.txt b/third_party/mavlink/CMakeLists.txt index 6278270c5f..5f7a419474 100644 --- a/third_party/mavlink/CMakeLists.txt +++ b/third_party/mavlink/CMakeLists.txt @@ -9,11 +9,13 @@ list(APPEND CMAKE_ARGS "-DMAVLINK_DIALECT=${MAVLINK_DIALECT}" ) +set(MAVLINK_GIT_HASH 9840105a275db1f48f9711d0fb861e8bf77a2245) + if(IOS) ExternalProject_add( mavlink GIT_REPOSITORY https://github.com/mavlink/mavlink - GIT_TAG 18955a04c7c7467e00ea42b704addb4a9c12b53a + GIT_TAG ${MAVLINK_GIT_HASH} PREFIX mavlink PATCH_COMMAND git checkout . COMMAND git apply ${PROJECT_SOURCE_DIR}/mavlink.patch @@ -24,7 +26,7 @@ else() ExternalProject_add( mavlink GIT_REPOSITORY https://github.com/mavlink/mavlink - GIT_TAG 81524c2b34aa08768f13091b1d94c421e64f96c3 + GIT_TAG ${MAVLINK_GIT_HASH} PREFIX mavlink PATCH_COMMAND git checkout . && git apply ${PROJECT_SOURCE_DIR}/mavlink.patch CMAKE_ARGS "${CMAKE_ARGS}" From c8d3afbbf30e1d75813c69963406d1347e411a63 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 25 Dec 2023 05:41:35 +1300 Subject: [PATCH 24/25] camera: fix cast Signed-off-by: Julian Oes --- src/mavsdk/plugins/camera/camera_impl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index be328068b4..e7a9d250d1 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -1944,7 +1944,7 @@ void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback MavlinkCommandSender::CommandLong cmd_format{}; cmd_format.command = MAV_CMD_STORAGE_FORMAT; - cmd_format.params.maybe_param1 = storage_id; // storage ID + cmd_format.params.maybe_param1 = static_cast(storage_id); // storage ID cmd_format.params.maybe_param2 = 1.0f; // format cmd_format.params.maybe_param3 = 1.0f; // clear cmd_format.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; From 38424a4070ce4f90308ad3fc2e02cfc54c636e59 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 25 Dec 2023 09:16:12 +1300 Subject: [PATCH 25/25] proto: update to main Signed-off-by: Julian Oes --- proto | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/proto b/proto index 8184c04888..a10b832c7a 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 8184c0488859bdfcdda4aa88efa46acccd9c204c +Subproject commit a10b832c7a342cf6a85ce771ea6671eef01ab892