diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index b70aba6672..73ec946d12 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -90,4 +90,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 baddeb949e..9b057d870c 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -159,4 +159,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 e8b5db2d76..6cad3803d2 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 c43b698f46..fecdf4338e 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 82d692a16e..f7d8aaf0e8 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -1955,22 +1955,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; @@ -1989,6 +1989,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 a56da68902..3fe334aa48 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 f2db627530..45fbb69fb1 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -492,6 +492,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. @@ -682,14 +703,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( @@ -727,10 +752,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 313d752688..1665da4c49 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);