From ad1d2eec4ac05d32a3f3c94328ee5845492499cf Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 29 Aug 2024 14:28:32 +1200 Subject: [PATCH] camera: support multiple cameras within one instance This changes the API to support more than one camera within one camera plugin instance. This will enable multiple cameras in language wrappers instead of just C++ as it is now. Work in progress ... --- proto | 2 +- src/mavsdk/plugins/camera/camera.cpp | 301 +- src/mavsdk/plugins/camera/camera_impl.cpp | 678 +- src/mavsdk/plugins/camera/camera_impl.h | 238 +- .../camera/include/plugins/camera/camera.h | 248 +- .../gimbal/include/plugins/gimbal/gimbal.h | 2 +- .../src/generated/camera/camera.grpc.pb.cc | 430 +- .../src/generated/camera/camera.grpc.pb.h | 1832 ++- .../src/generated/camera/camera.pb.cc | 9965 ++++++++++---- .../src/generated/camera/camera.pb.h | 10969 ++++++++++------ .../src/plugins/camera/camera_service_impl.h | 423 +- templates/mavsdk_server/request.j2 | 5 +- 12 files changed, 16913 insertions(+), 8180 deletions(-) diff --git a/proto b/proto index 517fef5a3a..8e92f5f796 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 517fef5a3a673e9b50f65a56dff350c6af515564 +Subproject commit 8e92f5f796ac44bc96b9f3dad98f63eccc49797d diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index 89555b6117..b8167e2f1b 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -9,6 +9,8 @@ namespace mavsdk { +using ModeInfo = Camera::ModeInfo; + using Position = Camera::Position; using Quaternion = Camera::Quaternion; using EulerAngle = Camera::EulerAngle; @@ -20,6 +22,7 @@ using Option = Camera::Option; using Setting = Camera::Setting; using SettingOptions = Camera::SettingOptions; using Information = Camera::Information; +using CameraList = Camera::CameraList; Camera::Camera(System& system) : PluginBase(), _impl{std::make_unique(system)} {} @@ -30,125 +33,117 @@ Camera::Camera(std::shared_ptr system) : Camera::~Camera() {} -void Camera::prepare_async(const ResultCallback callback) -{ - _impl->prepare_async(callback); -} - -Camera::Result Camera::prepare() const -{ - return _impl->prepare(); -} - -void Camera::take_photo_async(const ResultCallback callback) +void Camera::take_photo_async(int32_t camera_id, const ResultCallback callback) { - _impl->take_photo_async(callback); + _impl->take_photo_async(camera_id, callback); } -Camera::Result Camera::take_photo() const +Camera::Result Camera::take_photo(int32_t camera_id) const { - return _impl->take_photo(); + return _impl->take_photo(camera_id); } -void Camera::start_photo_interval_async(float interval_s, const ResultCallback callback) +void Camera::start_photo_interval_async( + int32_t camera_id, float interval_s, const ResultCallback callback) { - _impl->start_photo_interval_async(interval_s, callback); + _impl->start_photo_interval_async(camera_id, interval_s, callback); } -Camera::Result Camera::start_photo_interval(float interval_s) const +Camera::Result Camera::start_photo_interval(int32_t camera_id, float interval_s) const { - return _impl->start_photo_interval(interval_s); + return _impl->start_photo_interval(camera_id, interval_s); } -void Camera::stop_photo_interval_async(const ResultCallback callback) +void Camera::stop_photo_interval_async(int32_t camera_id, const ResultCallback callback) { - _impl->stop_photo_interval_async(callback); + _impl->stop_photo_interval_async(camera_id, callback); } -Camera::Result Camera::stop_photo_interval() const +Camera::Result Camera::stop_photo_interval(int32_t camera_id) const { - return _impl->stop_photo_interval(); + return _impl->stop_photo_interval(camera_id); } -void Camera::start_video_async(const ResultCallback callback) +void Camera::start_video_async(int32_t camera_id, const ResultCallback callback) { - _impl->start_video_async(callback); + _impl->start_video_async(camera_id, callback); } -Camera::Result Camera::start_video() const +Camera::Result Camera::start_video(int32_t camera_id) const { - return _impl->start_video(); + return _impl->start_video(camera_id); } -void Camera::stop_video_async(const ResultCallback callback) +void Camera::stop_video_async(int32_t camera_id, const ResultCallback callback) { - _impl->stop_video_async(callback); + _impl->stop_video_async(camera_id, callback); } -Camera::Result Camera::stop_video() const +Camera::Result Camera::stop_video(int32_t camera_id) const { - return _impl->stop_video(); + return _impl->stop_video(camera_id); } -Camera::Result Camera::start_video_streaming(int32_t stream_id) const +Camera::Result Camera::start_video_streaming(int32_t camera_id, int32_t stream_id) const { - return _impl->start_video_streaming(stream_id); + return _impl->start_video_streaming(camera_id, stream_id); } -Camera::Result Camera::stop_video_streaming(int32_t stream_id) const +Camera::Result Camera::stop_video_streaming(int32_t camera_id, int32_t stream_id) const { - return _impl->stop_video_streaming(stream_id); + return _impl->stop_video_streaming(camera_id, stream_id); } -void Camera::set_mode_async(Mode mode, const ResultCallback callback) +void Camera::set_mode_async(int32_t camera_id, Mode mode, const ResultCallback callback) { - _impl->set_mode_async(mode, callback); + _impl->set_mode_async(camera_id, mode, callback); } -Camera::Result Camera::set_mode(Mode mode) const +Camera::Result Camera::set_mode(int32_t camera_id, Mode mode) const { - return _impl->set_mode(mode); + return _impl->set_mode(camera_id, mode); } -void Camera::list_photos_async(PhotosRange photos_range, const ListPhotosCallback callback) +void Camera::list_photos_async( + int32_t camera_id, PhotosRange photos_range, const ListPhotosCallback callback) { - _impl->list_photos_async(photos_range, callback); + _impl->list_photos_async(camera_id, photos_range, callback); } std::pair> -Camera::list_photos(PhotosRange photos_range) const +Camera::list_photos(int32_t camera_id, PhotosRange photos_range) const { - return _impl->list_photos(photos_range); + return _impl->list_photos(camera_id, photos_range); } -Camera::ModeHandle Camera::subscribe_mode(const ModeCallback& callback) +Camera::CameraListHandle Camera::subscribe_camera_list(const CameraListCallback& callback) { - return _impl->subscribe_mode(callback); + return _impl->subscribe_camera_list(callback); } -void Camera::unsubscribe_mode(ModeHandle handle) +void Camera::unsubscribe_camera_list(CameraListHandle handle) { - _impl->unsubscribe_mode(handle); + _impl->unsubscribe_camera_list(handle); } -Camera::Mode Camera::mode() const +Camera::CameraList Camera::camera_list() const { - return _impl->mode(); + return _impl->camera_list(); } -Camera::InformationHandle Camera::subscribe_information(const InformationCallback& callback) +Camera::ModeHandle Camera::subscribe_mode(const ModeCallback& callback) { - return _impl->subscribe_information(callback); + return _impl->subscribe_mode(callback); } -void Camera::unsubscribe_information(InformationHandle handle) +void Camera::unsubscribe_mode(ModeHandle handle) { - _impl->unsubscribe_information(handle); + _impl->unsubscribe_mode(handle); } -Camera::Information Camera::information() const +Camera::Mode Camera::get_mode(int32_t camera_id) const { - return _impl->information(); + return _impl->get_mode(camera_id); } Camera::VideoStreamInfoHandle @@ -162,9 +157,9 @@ void Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle) _impl->unsubscribe_video_stream_info(handle); } -Camera::VideoStreamInfo Camera::video_stream_info() const +Camera::VideoStreamInfo Camera::get_video_stream_info(int32_t camera_id) const { - return _impl->video_stream_info(); + return _impl->get_video_stream_info(camera_id); } Camera::CaptureInfoHandle Camera::subscribe_capture_info(const CaptureInfoCallback& callback) @@ -187,9 +182,9 @@ void Camera::unsubscribe_status(StatusHandle handle) _impl->unsubscribe_status(handle); } -Camera::Status Camera::status() const +Camera::Status Camera::get_status(int32_t camera_id) const { - return _impl->status(); + return _impl->get_status(camera_id); } Camera::CurrentSettingsHandle @@ -203,6 +198,12 @@ void Camera::unsubscribe_current_settings(CurrentSettingsHandle handle) _impl->unsubscribe_current_settings(handle); } +std::pair> +Camera::get_current_settings(int32_t camera_id) const +{ + return _impl->get_current_settings(camera_id); +} + Camera::PossibleSettingOptionsHandle Camera::subscribe_possible_setting_options(const PossibleSettingOptionsCallback& callback) { @@ -214,171 +215,193 @@ void Camera::unsubscribe_possible_setting_options(PossibleSettingOptionsHandle h _impl->unsubscribe_possible_setting_options(handle); } -std::vector Camera::possible_setting_options() const +std::pair> +Camera::get_possible_setting_options(int32_t camera_id) const { - return _impl->possible_setting_options(); + return _impl->get_possible_setting_options(camera_id); } -void Camera::set_setting_async(Setting setting, const ResultCallback callback) +void Camera::set_setting_async(int32_t camera_id, Setting setting, const ResultCallback callback) { - _impl->set_setting_async(setting, callback); + _impl->set_setting_async(camera_id, setting, callback); } -Camera::Result Camera::set_setting(Setting setting) const +Camera::Result Camera::set_setting(int32_t camera_id, Setting setting) const { - return _impl->set_setting(setting); + return _impl->set_setting(camera_id, setting); } -void Camera::get_setting_async(Setting setting, const GetSettingCallback callback) +void Camera::get_setting_async( + int32_t camera_id, Setting setting, const GetSettingCallback callback) { - _impl->get_setting_async(setting, callback); + _impl->get_setting_async(camera_id, setting, callback); } -std::pair Camera::get_setting(Setting setting) const +std::pair +Camera::get_setting(int32_t camera_id, Setting setting) const { - return _impl->get_setting(setting); + return _impl->get_setting(camera_id, setting); } -void Camera::format_storage_async(int32_t storage_id, const ResultCallback callback) +void Camera::format_storage_async( + int32_t camera_id, int32_t storage_id, const ResultCallback callback) { - _impl->format_storage_async(storage_id, callback); + _impl->format_storage_async(camera_id, storage_id, callback); } -Camera::Result Camera::format_storage(int32_t storage_id) const +Camera::Result Camera::format_storage(int32_t camera_id, int32_t storage_id) const { - return _impl->format_storage(storage_id); + return _impl->format_storage(camera_id, storage_id); } -Camera::Result Camera::select_camera(int32_t camera_id) const +void Camera::reset_settings_async(int32_t camera_id, const ResultCallback callback) { - return _impl->select_camera(camera_id); + _impl->reset_settings_async(camera_id, callback); } -void Camera::reset_settings_async(const ResultCallback callback) +Camera::Result Camera::reset_settings(int32_t camera_id) const { - _impl->reset_settings_async(callback); + return _impl->reset_settings(camera_id); } -Camera::Result Camera::reset_settings() const +void Camera::zoom_in_start_async(int32_t camera_id, const ResultCallback callback) { - return _impl->reset_settings(); + _impl->zoom_in_start_async(camera_id, callback); } -void Camera::zoom_in_start_async(const ResultCallback callback) +Camera::Result Camera::zoom_in_start(int32_t camera_id) const { - _impl->zoom_in_start_async(callback); + return _impl->zoom_in_start(camera_id); } -Camera::Result Camera::zoom_in_start() const +void Camera::zoom_out_start_async(int32_t camera_id, const ResultCallback callback) { - return _impl->zoom_in_start(); + _impl->zoom_out_start_async(camera_id, callback); } -void Camera::zoom_out_start_async(const ResultCallback callback) +Camera::Result Camera::zoom_out_start(int32_t camera_id) const { - _impl->zoom_out_start_async(callback); + return _impl->zoom_out_start(camera_id); } -Camera::Result Camera::zoom_out_start() const +void Camera::zoom_stop_async(int32_t camera_id, const ResultCallback callback) { - return _impl->zoom_out_start(); + _impl->zoom_stop_async(camera_id, callback); } -void Camera::zoom_stop_async(const ResultCallback callback) +Camera::Result Camera::zoom_stop(int32_t camera_id) const { - _impl->zoom_stop_async(callback); + return _impl->zoom_stop(camera_id); } -Camera::Result Camera::zoom_stop() const +void Camera::zoom_range_async(int32_t camera_id, float range, const ResultCallback callback) { - return _impl->zoom_stop(); + _impl->zoom_range_async(camera_id, range, callback); } -void Camera::zoom_range_async(float range, const ResultCallback callback) +Camera::Result Camera::zoom_range(int32_t camera_id, float range) const { - _impl->zoom_range_async(range, callback); -} - -Camera::Result Camera::zoom_range(float range) const -{ - return _impl->zoom_range(range); + return _impl->zoom_range(camera_id, range); } void Camera::track_point_async( - float point_x, float point_y, float radius, const ResultCallback callback) + int32_t camera_id, float point_x, float point_y, float radius, const ResultCallback callback) { - _impl->track_point_async(point_x, point_y, radius, callback); + _impl->track_point_async(camera_id, point_x, point_y, radius, callback); } -Camera::Result Camera::track_point(float point_x, float point_y, float radius) const +Camera::Result +Camera::track_point(int32_t camera_id, float point_x, float point_y, float radius) const { - return _impl->track_point(point_x, point_y, radius); + return _impl->track_point(camera_id, point_x, point_y, radius); } void Camera::track_rectangle_async( + int32_t camera_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const ResultCallback callback) { - _impl->track_rectangle_async(top_left_x, top_left_y, bottom_right_x, bottom_right_y, callback); + _impl->track_rectangle_async( + camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y, callback); } Camera::Result Camera::track_rectangle( - float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y) const +{ + return _impl->track_rectangle( + camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y); +} + +void Camera::track_stop_async(int32_t camera_id, const ResultCallback callback) { - return _impl->track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y); + _impl->track_stop_async(camera_id, callback); } -void Camera::track_stop_async(const ResultCallback callback) +Camera::Result Camera::track_stop(int32_t camera_id) const { - _impl->track_stop_async(callback); + return _impl->track_stop(camera_id); } -Camera::Result Camera::track_stop() const +void Camera::focus_in_start_async(int32_t camera_id, const ResultCallback callback) { - return _impl->track_stop(); + _impl->focus_in_start_async(camera_id, callback); } -void Camera::focus_in_start_async(const ResultCallback callback) +Camera::Result Camera::focus_in_start(int32_t camera_id) const { - _impl->focus_in_start_async(callback); + return _impl->focus_in_start(camera_id); } -Camera::Result Camera::focus_in_start() const +void Camera::focus_out_start_async(int32_t camera_id, const ResultCallback callback) { - return _impl->focus_in_start(); + _impl->focus_out_start_async(camera_id, callback); } -void Camera::focus_out_start_async(const ResultCallback callback) +Camera::Result Camera::focus_out_start(int32_t camera_id) const { - _impl->focus_out_start_async(callback); + return _impl->focus_out_start(camera_id); } -Camera::Result Camera::focus_out_start() const +void Camera::focus_stop_async(int32_t camera_id, const ResultCallback callback) { - return _impl->focus_out_start(); + _impl->focus_stop_async(camera_id, callback); } -void Camera::focus_stop_async(const ResultCallback callback) +Camera::Result Camera::focus_stop(int32_t camera_id) const { - _impl->focus_stop_async(callback); + return _impl->focus_stop(camera_id); } -Camera::Result Camera::focus_stop() const +void Camera::focus_range_async(int32_t camera_id, float range, const ResultCallback callback) { - return _impl->focus_stop(); + _impl->focus_range_async(camera_id, range, callback); } -void Camera::focus_range_async(float range, const ResultCallback callback) +Camera::Result Camera::focus_range(int32_t camera_id, float range) const { - _impl->focus_range_async(range, callback); + return _impl->focus_range(camera_id, range); } -Camera::Result Camera::focus_range(float range) const +bool operator==(const Camera::ModeInfo& lhs, const Camera::ModeInfo& rhs) { - return _impl->focus_range(range); + return (rhs.camera_id == lhs.camera_id) && (rhs.mode == lhs.mode); +} + +std::ostream& operator<<(std::ostream& str, Camera::ModeInfo const& mode_info) +{ + str << std::setprecision(15); + str << "mode_info:" << '\n' << "{\n"; + str << " camera_id: " << mode_info.camera_id << '\n'; + str << " mode: " << mode_info.mode << '\n'; + str << '}'; + return str; } std::ostream& operator<<(std::ostream& str, Camera::Result const& result) @@ -554,14 +577,15 @@ std::ostream& operator<<( } bool operator==(const Camera::VideoStreamInfo& lhs, const Camera::VideoStreamInfo& rhs) { - return (rhs.settings == lhs.settings) && (rhs.status == lhs.status) && - (rhs.spectrum == lhs.spectrum); + return (rhs.camera_id == lhs.camera_id) && (rhs.settings == lhs.settings) && + (rhs.status == lhs.status) && (rhs.spectrum == lhs.spectrum); } std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info) { str << std::setprecision(15); str << "video_stream_info:" << '\n' << "{\n"; + str << " camera_id: " << video_stream_info.camera_id << '\n'; str << " settings: " << video_stream_info.settings << '\n'; str << " status: " << video_stream_info.status << '\n'; str << " spectrum: " << video_stream_info.spectrum << '\n'; @@ -606,7 +630,8 @@ std::ostream& operator<<(std::ostream& str, Camera::Status::StorageType const& s } bool operator==(const Camera::Status& lhs, const Camera::Status& rhs) { - return (rhs.video_on == lhs.video_on) && (rhs.photo_interval_on == lhs.photo_interval_on) && + return (rhs.camera_id == lhs.camera_id) && (rhs.video_on == lhs.video_on) && + (rhs.photo_interval_on == lhs.photo_interval_on) && ((std::isnan(rhs.used_storage_mib) && std::isnan(lhs.used_storage_mib)) || rhs.used_storage_mib == lhs.used_storage_mib) && ((std::isnan(rhs.available_storage_mib) && std::isnan(lhs.available_storage_mib)) || @@ -624,6 +649,7 @@ std::ostream& operator<<(std::ostream& str, Camera::Status const& status) { str << std::setprecision(15); str << "status:" << '\n' << "{\n"; + str << " camera_id: " << status.camera_id << '\n'; str << " video_on: " << status.video_on << '\n'; str << " photo_interval_on: " << status.photo_interval_on << '\n'; str << " used_storage_mib: " << status.used_storage_mib << '\n'; @@ -674,7 +700,7 @@ std::ostream& operator<<(std::ostream& str, Camera::Setting const& setting) bool operator==(const Camera::SettingOptions& lhs, const Camera::SettingOptions& rhs) { - return (rhs.setting_id == lhs.setting_id) && + return (rhs.camera_id == lhs.camera_id) && (rhs.setting_id == lhs.setting_id) && (rhs.setting_description == lhs.setting_description) && (rhs.options == lhs.options) && (rhs.is_range == lhs.is_range); } @@ -683,6 +709,7 @@ std::ostream& operator<<(std::ostream& str, Camera::SettingOptions const& settin { str << std::setprecision(15); str << "setting_options:" << '\n' << "{\n"; + str << " camera_id: " << setting_options.camera_id << '\n'; str << " setting_id: " << setting_options.setting_id << '\n'; str << " setting_description: " << setting_options.setting_description << '\n'; str << " options: ["; @@ -724,6 +751,24 @@ std::ostream& operator<<(std::ostream& str, Camera::Information const& informati return str; } +bool operator==(const Camera::CameraList& lhs, const Camera::CameraList& rhs) +{ + return (rhs.cameras == lhs.cameras); +} + +std::ostream& operator<<(std::ostream& str, Camera::CameraList const& camera_list) +{ + str << std::setprecision(15); + str << "camera_list:" << '\n' << "{\n"; + str << " cameras: ["; + for (auto it = camera_list.cameras.begin(); it != camera_list.cameras.end(); ++it) { + str << *it; + str << (it + 1 != camera_list.cameras.end() ? ", " : "]\n"); + } + str << '}'; + return str; +} + std::ostream& operator<<(std::ostream& str, Camera::Mode const& mode) { switch (mode) { diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 716b739352..8b728372ea 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -12,6 +12,7 @@ #include #include #include +#include #include namespace mavsdk { @@ -40,114 +41,101 @@ CameraImpl::~CameraImpl() void CameraImpl::init() { - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( + MAVLINK_MSG_ID_HEARTBEAT, + [this](const mavlink_message_t& message) { process_heartbeat(message); }, + this); + + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_camera_capture_status(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_STORAGE_INFORMATION, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_storage_information(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_camera_image_captured(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_CAMERA_SETTINGS, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_camera_settings(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_CAMERA_INFORMATION, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_camera_information(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_video_information(message); }, this); - _system_impl->register_mavlink_message_handler_with_compid( + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, - _camera_id + MAV_COMP_ID_CAMERA, [this](const mavlink_message_t& message) { process_video_stream_status(message); }, this); - _check_connection_status_call_every_cookie = - _system_impl->add_call_every([this]() { check_connection_status(); }, 0.5); - - _request_missing_capture_info_cookie = - _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5); + //_request_missing_capture_info_cookie = + // _system_impl->add_call_every([this]() { request_missing_capture_info(); }, 0.5); } void CameraImpl::deinit() { - _system_impl->remove_call_every(_request_missing_capture_info_cookie); - _system_impl->remove_call_every(_check_connection_status_call_every_cookie); - _system_impl->remove_call_every(_status.call_every_cookie); - _system_impl->remove_call_every(_camera_information_call_every_cookie); - _system_impl->remove_call_every(_mode.call_every_cookie); - _system_impl->remove_call_every(_video_stream_info.call_every_cookie); _system_impl->unregister_all_mavlink_message_handlers(this); - _system_impl->cancel_all_param(this); - - { - std::lock_guard lock(_status.mutex); - _status.subscription_callbacks.clear(); - } - { - std::lock_guard lock(_mode.mutex); - _mode.subscription_callbacks.clear(); - } + //_system_impl->remove_call_every(_request_missing_capture_info_cookie); + //_system_impl->remove_call_every(_status.call_every_cookie); + //_system_impl->remove_call_every(_camera_information_call_every_cookie); + //_system_impl->remove_call_every(_mode.call_every_cookie); + //_system_impl->remove_call_every(_video_stream_info.call_every_cookie); + //_system_impl->cancel_all_param(this); - { - std::lock_guard lock(_capture_info.mutex); - _capture_info.callbacks.clear(); - } - - { - std::lock_guard lock(_video_stream_info.mutex); - _video_stream_info.subscription_callbacks.clear(); - } + //{ + // std::lock_guard lock(_status.mutex); + // _status.subscription_callbacks.clear(); + //} - { - std::lock_guard lock(_information.mutex); - _information.subscription_callbacks.clear(); - } + //{ + // std::lock_guard lock(_mode.mutex); + // _mode.subscription_callbacks.clear(); + //} - { - std::lock_guard lock(_subscribe_current_settings.mutex); - _subscribe_current_settings.callbacks.clear(); - } + //{ + // std::lock_guard lock(_capture_info.mutex); + // _capture_info.callbacks.clear(); + //} - { - std::lock_guard lock(_subscribe_possible_setting_options.mutex); - _subscribe_possible_setting_options.callbacks.clear(); - } + //{ + // std::lock_guard lock(_video_stream_info.mutex); + // _video_stream_info.subscription_callbacks.clear(); + //} - _camera_found = false; -} + //{ + // std::lock_guard lock(_camera_list.mutex); + // _camera_list.subscription_callbacks.clear(); + //} -Camera::Result CameraImpl::prepare() -{ - auto prom = std::make_shared>(); - auto ret = prom->get_future(); + //{ + // std::lock_guard lock(_subscribe_current_settings.mutex); + // _subscribe_current_settings.callbacks.clear(); + //} - prepare_async([&prom](Camera::Result result) { prom->set_value(result); }); + //{ + // std::lock_guard lock(_subscribe_possible_setting_options.mutex); + // _subscribe_possible_setting_options.callbacks.clear(); + //} - return ret.get(); + //_camera_found = false; } +#if 0 +// TODO: add again void CameraImpl::prepare_async(const Camera::ResultCallback& callback) { auto temp_callback = callback; @@ -170,19 +158,7 @@ void CameraImpl::prepare_async(const Camera::ResultCallback& callback) } } } - -void CameraImpl::check_connection_status() -{ - // FIXME: This is a workaround because we don't want to be tied to the - // discovery of an autopilot which triggers enable() and disable() but - // we are interested if a camera is connected or not. - if (_system_impl->has_camera(_camera_id)) { - if (!_camera_found) { - _camera_found = true; - manual_enable(); - } - } -} +#endif void CameraImpl::enable() { @@ -191,6 +167,8 @@ void CameraImpl::enable() // but only the camera. } +#if 0 + // TODO: add back in void CameraImpl::manual_enable() { refresh_params(); @@ -203,6 +181,7 @@ void CameraImpl::manual_enable() _status.call_every_cookie = _system_impl->add_call_every([this]() { request_status(); }, 5.0); } +#endif void CameraImpl::disable() { @@ -211,6 +190,8 @@ void CameraImpl::disable() // but only the camera. } +#if 0 +// TODO remove void CameraImpl::manual_disable() { invalidate_params(); @@ -219,32 +200,10 @@ void CameraImpl::manual_disable() _camera_found = false; } +#endif -void CameraImpl::update_component() -{ - uint8_t cmp_id = _camera_id + MAV_COMP_ID_CAMERA; - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_STORAGE_INFORMATION, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_CAMERA_SETTINGS, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_CAMERA_INFORMATION, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, cmp_id, this); - - _system_impl->update_component_id_messages_handler( - MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, cmp_id, this); -} - +#if 0 +// TODO: get rid of Camera::Result CameraImpl::select_camera(const size_t id) { static constexpr std::size_t MAX_SUPPORTED_ID = 5; @@ -264,56 +223,58 @@ Camera::Result CameraImpl::select_camera(const size_t id) return Camera::Result::Success; } +#endif MavlinkCommandSender::CommandLong -CameraImpl::make_command_take_photo(float interval_s, float no_of_photos) +CameraImpl::make_command_take_photo(int32_t camera_id, float interval_s, float no_of_photos) { - MavlinkCommandSender::CommandLong cmd_take_photo{}; + MavlinkCommandSender::CommandLong cmd{}; - cmd_take_photo.command = MAV_CMD_IMAGE_START_CAPTURE; - cmd_take_photo.params.maybe_param1 = 0.0f; // Reserved, set to 0 - cmd_take_photo.params.maybe_param2 = interval_s; - cmd_take_photo.params.maybe_param3 = no_of_photos; - cmd_take_photo.params.maybe_param4 = static_cast(_capture.sequence++); - cmd_take_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.command = MAV_CMD_IMAGE_START_CAPTURE; + cmd.params.maybe_param1 = 0.0f; // Reserved, set to 0 + cmd.params.maybe_param2 = interval_s; + cmd.params.maybe_param3 = no_of_photos; + cmd.params.maybe_param4 = static_cast(_capture.sequence++); + cmd.target_component_id = component_id_for_camera_id(camera_id); - return cmd_take_photo; + return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out() +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; cmd.params.maybe_param2 = -1.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in() +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; cmd.params.maybe_param2 = 1.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop() +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; cmd.params.maybe_param2 = 0.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_range(float range) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_zoom_range(int32_t camera_id, float range) { // Clip to safe range. range = std::max(0.f, std::min(range, 100.f)); @@ -322,26 +283,30 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_range(float rang cmd.command = MAV_CMD_SET_CAMERA_ZOOM; cmd.params.maybe_param1 = (float)ZOOM_TYPE_RANGE; cmd.params.maybe_param2 = range; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } MavlinkCommandSender::CommandLong -CameraImpl::make_command_track_point(float point_x, float point_y, float radius) +CameraImpl::make_command_track_point(int32_t camera_id, float point_x, float point_y, float radius) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_CAMERA_TRACK_POINT; cmd.params.maybe_param1 = (float)point_x; cmd.params.maybe_param2 = (float)point_y; cmd.params.maybe_param3 = (float)radius; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle( - float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_CAMERA_TRACK_RECTANGLE; @@ -349,49 +314,50 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle( cmd.params.maybe_param2 = top_left_y; cmd.params.maybe_param3 = bottom_right_x; cmd.params.maybe_param4 = bottom_right_y; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop() +MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_CAMERA_STOP_TRACKING; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in() +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; cmd.params.maybe_param2 = -1.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out() +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; cmd.params.maybe_param2 = 1.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop() +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; cmd.params.maybe_param2 = 0.f; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_range(float range) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_focus_range(int32_t camera_id, float range) { // Clip to safe range. range = std::max(0.f, std::min(range, 100.f)); @@ -400,191 +366,251 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_range(float ran cmd.command = MAV_CMD_SET_CAMERA_FOCUS; cmd.params.maybe_param1 = (float)FOCUS_TYPE_RANGE; cmd.params.maybe_param2 = range; - cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo() +MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd_stop_photo{}; cmd_stop_photo.command = MAV_CMD_IMAGE_STOP_CAPTURE; - cmd_stop_photo.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_stop_photo.target_component_id = component_id_for_camera_id(camera_id); return cmd_stop_photo; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video(float capture_status_rate_hz) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_start_video(int32_t camera_id, float capture_status_rate_hz) { MavlinkCommandSender::CommandLong cmd_start_video{}; cmd_start_video.command = MAV_CMD_VIDEO_START_CAPTURE; cmd_start_video.params.maybe_param1 = 0.f; // Reserved, set to 0 cmd_start_video.params.maybe_param2 = capture_status_rate_hz; - cmd_start_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_start_video.target_component_id = component_id_for_camera_id(camera_id); return cmd_start_video; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video() +MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd_stop_video{}; cmd_stop_video.command = MAV_CMD_VIDEO_STOP_CAPTURE; cmd_stop_video.params.maybe_param1 = 0.f; // Reserved, set to 0 - cmd_stop_video.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_stop_video.target_component_id = component_id_for_camera_id(camera_id); return cmd_stop_video; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_set_camera_mode(float mavlink_mode) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_set_camera_mode(int32_t camera_id, float mavlink_mode) { MavlinkCommandSender::CommandLong cmd_set_camera_mode{}; cmd_set_camera_mode.command = MAV_CMD_SET_CAMERA_MODE; cmd_set_camera_mode.params.maybe_param1 = 0.0f; // Reserved, set to 0 cmd_set_camera_mode.params.maybe_param2 = mavlink_mode; - cmd_set_camera_mode.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_set_camera_mode.target_component_id = component_id_for_camera_id(camera_id); return cmd_set_camera_mode; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming(int32_t stream_id) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_request_camera_settings(int32_t camera_id) +{ + MavlinkCommandSender::CommandLong cmd_req_camera_settings{}; + + cmd_req_camera_settings.command = MAV_CMD_REQUEST_CAMERA_SETTINGS; + cmd_req_camera_settings.params.maybe_param1 = 1.f; // Request it + cmd_req_camera_settings.target_component_id = component_id_for_camera_id(camera_id); + + return cmd_req_camera_settings; +} + +MavlinkCommandSender::CommandLong +CameraImpl::make_command_request_camera_capture_status(int32_t camera_id) +{ + MavlinkCommandSender::CommandLong cmd_req_camera_cap_stat{}; + + cmd_req_camera_cap_stat.command = MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS; + cmd_req_camera_cap_stat.params.maybe_param1 = 1.0f; // Request it + cmd_req_camera_cap_stat.target_component_id = component_id_for_camera_id(camera_id); + + return cmd_req_camera_cap_stat; +} + +MavlinkCommandSender::CommandLong +CameraImpl::make_command_request_camera_image_captured(int32_t camera_id, const size_t photo_id) +{ + MavlinkCommandSender::CommandLong cmd_req_camera_image_captured{}; + + cmd_req_camera_image_captured.command = MAV_CMD_REQUEST_MESSAGE; + cmd_req_camera_image_captured.params.maybe_param1 = + static_cast(MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED); + cmd_req_camera_image_captured.params.maybe_param2 = static_cast(photo_id); + cmd_req_camera_image_captured.target_component_id = component_id_for_camera_id(camera_id); + + return cmd_req_camera_image_captured; +} + +MavlinkCommandSender::CommandLong CameraImpl::make_command_request_storage_info(int32_t camera_id) +{ + MavlinkCommandSender::CommandLong cmd_req_storage_info{}; + + cmd_req_storage_info.command = MAV_CMD_REQUEST_STORAGE_INFORMATION; + cmd_req_storage_info.params.maybe_param1 = 0.f; // Reserved, set to 0 + cmd_req_storage_info.params.maybe_param2 = 1.f; // Request it + cmd_req_storage_info.target_component_id = component_id_for_camera_id(camera_id); + + return cmd_req_storage_info; +} + +MavlinkCommandSender::CommandLong +CameraImpl::make_command_start_video_streaming(int32_t camera_id, int32_t stream_id) { MavlinkCommandSender::CommandLong cmd_start_video_streaming{}; cmd_start_video_streaming.command = MAV_CMD_VIDEO_START_STREAMING; cmd_start_video_streaming.params.maybe_param1 = static_cast(stream_id); - cmd_start_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_start_video_streaming.target_component_id = component_id_for_camera_id(camera_id); return cmd_start_video_streaming; } -MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_video_streaming(int32_t stream_id) +MavlinkCommandSender::CommandLong +CameraImpl::make_command_stop_video_streaming(int32_t camera_id, int32_t stream_id) { MavlinkCommandSender::CommandLong cmd_stop_video_streaming{}; cmd_stop_video_streaming.command = MAV_CMD_VIDEO_STOP_STREAMING; cmd_stop_video_streaming.params.maybe_param1 = static_cast(stream_id); - cmd_stop_video_streaming.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + cmd_stop_video_streaming.target_component_id = component_id_for_camera_id(camera_id); return cmd_stop_video_streaming; } -Camera::Result CameraImpl::take_photo() +Camera::Result CameraImpl::take_photo(int32_t camera_id) { // TODO: check whether we are in photo mode. std::lock_guard lock(_capture.mutex); // Take 1 photo only with no interval - auto cmd_take_photo = make_command_take_photo(0.f, 1.0f); + auto cmd_take_photo = make_command_take_photo(camera_id, 0.f, 1.0f); return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo)); } -Camera::Result CameraImpl::zoom_out_start() +Camera::Result CameraImpl::zoom_out_start(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_out(); + auto cmd = make_command_zoom_out(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::zoom_in_start() +Camera::Result CameraImpl::zoom_in_start(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_in(); + auto cmd = make_command_zoom_in(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::zoom_stop() +Camera::Result CameraImpl::zoom_stop(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_stop(); + auto cmd = make_command_zoom_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::zoom_range(float range) +Camera::Result CameraImpl::zoom_range(int32_t camera_id, float range) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_range(range); + auto cmd = make_command_zoom_range(camera_id, range); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::track_point(float point_x, float point_y, float radius) +Camera::Result +CameraImpl::track_point(int32_t camera_id, float point_x, float point_y, float radius) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_point(point_x, point_y, radius); + auto cmd = make_command_track_point(camera_id, point_x, point_y, radius); return camera_result_from_command_result(_system_impl->send_command(cmd)); } Camera::Result CameraImpl::track_rectangle( - float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y); + auto cmd = make_command_track_rectangle( + camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::track_stop() +Camera::Result CameraImpl::track_stop(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_stop(); + auto cmd = make_command_track_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::focus_in_start() +Camera::Result CameraImpl::focus_in_start(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_in(); + auto cmd = make_command_focus_in(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::focus_out_start() +Camera::Result CameraImpl::focus_out_start(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_out(); + auto cmd = make_command_focus_out(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::focus_stop() +Camera::Result CameraImpl::focus_stop(int32_t camera_id) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_stop(); + auto cmd = make_command_focus_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::focus_range(float range) +Camera::Result CameraImpl::focus_range(int32_t camera_id, float range) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_range(range); + auto cmd = make_command_focus_range(camera_id, range); return camera_result_from_command_result(_system_impl->send_command(cmd)); } -Camera::Result CameraImpl::start_photo_interval(float interval_s) +Camera::Result CameraImpl::start_photo_interval(int32_t camera_id, float interval_s) { if (!interval_valid(interval_s)) { return Camera::Result::WrongArgument; @@ -594,32 +620,32 @@ Camera::Result CameraImpl::start_photo_interval(float interval_s) std::lock_guard lock(_capture.mutex); - auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f); + auto cmd_take_photo_time_lapse = make_command_take_photo(camera_id, interval_s, 0.f); return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse)); } -Camera::Result CameraImpl::stop_photo_interval() +Camera::Result CameraImpl::stop_photo_interval(int32_t camera_id) { - auto cmd_stop_photo_interval = make_command_stop_photo(); + auto cmd_stop_photo_interval = make_command_stop_photo(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd_stop_photo_interval)); } -Camera::Result CameraImpl::start_video() +Camera::Result CameraImpl::start_video(int32_t camera_id) { // TODO: check whether video capture is already in progress. // TODO: check whether we are in video mode. // Capture status rate is not set - auto cmd_start_video = make_command_start_video(0.f); + auto cmd_start_video = make_command_start_video(camera_id, 0.f); return camera_result_from_command_result(_system_impl->send_command(cmd_start_video)); } -Camera::Result CameraImpl::stop_video() +Camera::Result CameraImpl::stop_video(int32_t camera_id) { - auto cmd_stop_video = make_command_stop_video(); + auto cmd_stop_video = make_command_stop_video(camera_id); { std::lock_guard lock(_video_stream_info.mutex); @@ -629,11 +655,11 @@ Camera::Result CameraImpl::stop_video() return camera_result_from_command_result(_system_impl->send_command(cmd_stop_video)); } -void CameraImpl::zoom_in_start_async(const Camera::ResultCallback& callback) +void CameraImpl::zoom_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_in(); + auto cmd = make_command_zoom_in(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -641,11 +667,11 @@ void CameraImpl::zoom_in_start_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::zoom_out_start_async(const Camera::ResultCallback& callback) +void CameraImpl::zoom_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_out(); + auto cmd = make_command_zoom_out(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -653,11 +679,11 @@ void CameraImpl::zoom_out_start_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::zoom_stop_async(const Camera::ResultCallback& callback) +void CameraImpl::zoom_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_stop(); + auto cmd = make_command_zoom_stop(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -665,11 +691,12 @@ void CameraImpl::zoom_stop_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::zoom_range_async(float range, const Camera::ResultCallback& callback) +void CameraImpl::zoom_range_async( + int32_t camera_id, float range, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_range(range); + auto cmd = make_command_zoom_range(camera_id, range); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -678,11 +705,15 @@ void CameraImpl::zoom_range_async(float range, const Camera::ResultCallback& cal } void CameraImpl::track_point_async( - float point_x, float point_y, float radius, const Camera::ResultCallback& callback) + int32_t camera_id, + float point_x, + float point_y, + float radius, + const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_point(point_x, point_y, radius); + auto cmd = make_command_track_point(camera_id, point_x, point_y, radius); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -691,6 +722,7 @@ void CameraImpl::track_point_async( } void CameraImpl::track_rectangle_async( + int32_t camera_id, float top_left_x, float top_left_y, float bottom_right_x, @@ -699,7 +731,8 @@ void CameraImpl::track_rectangle_async( { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y); + auto cmd = make_command_track_rectangle( + camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -707,11 +740,11 @@ void CameraImpl::track_rectangle_async( }); } -void CameraImpl::track_stop_async(const Camera::ResultCallback& callback) +void CameraImpl::track_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_stop(); + auto cmd = make_command_track_stop(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -719,11 +752,11 @@ void CameraImpl::track_stop_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::focus_in_start_async(const Camera::ResultCallback& callback) +void CameraImpl::focus_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_in(); + auto cmd = make_command_focus_in(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -731,11 +764,11 @@ void CameraImpl::focus_in_start_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::focus_out_start_async(const Camera::ResultCallback& callback) +void CameraImpl::focus_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_out(); + auto cmd = make_command_focus_out(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -743,11 +776,11 @@ void CameraImpl::focus_out_start_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::focus_stop_async(const Camera::ResultCallback& callback) +void CameraImpl::focus_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_stop(); + auto cmd = make_command_focus_stop(camera_id); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -755,11 +788,12 @@ void CameraImpl::focus_stop_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::focus_range_async(float range, const Camera::ResultCallback& callback) +void CameraImpl::focus_range_async( + int32_t camera_id, float range, const Camera::ResultCallback& callback) { std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_range(range); + auto cmd = make_command_focus_range(camera_id, range); _system_impl->send_command_async( cmd, [this, callback](MavlinkCommandSender::Result result, float) { @@ -767,14 +801,14 @@ void CameraImpl::focus_range_async(float range, const Camera::ResultCallback& ca }); } -void CameraImpl::take_photo_async(const Camera::ResultCallback& callback) +void CameraImpl::take_photo_async(int32_t camera_id, const Camera::ResultCallback& callback) { // TODO: check whether we are in photo mode. std::lock_guard lock(_capture.mutex); // Take 1 photo only with no interval - auto cmd_take_photo = make_command_take_photo(0.f, 1.0f); + auto cmd_take_photo = make_command_take_photo(camera_id, 0.f, 1.0f); _system_impl->send_command_async( cmd_take_photo, [this, callback](MavlinkCommandSender::Result result, float) { @@ -783,7 +817,7 @@ void CameraImpl::take_photo_async(const Camera::ResultCallback& callback) } void CameraImpl::start_photo_interval_async( - float interval_s, const Camera::ResultCallback& callback) + int32_t camera_id, float interval_s, const Camera::ResultCallback& callback) { if (!interval_valid(interval_s)) { const auto temp_callback = callback; @@ -796,7 +830,7 @@ void CameraImpl::start_photo_interval_async( std::lock_guard lock(_capture.mutex); - auto cmd_take_photo_time_lapse = make_command_take_photo(interval_s, 0.f); + auto cmd_take_photo_time_lapse = make_command_take_photo(camera_id, interval_s, 0.f); _system_impl->send_command_async( cmd_take_photo_time_lapse, [this, callback](MavlinkCommandSender::Result result, float) { @@ -804,9 +838,10 @@ void CameraImpl::start_photo_interval_async( }); } -void CameraImpl::stop_photo_interval_async(const Camera::ResultCallback& callback) +void CameraImpl::stop_photo_interval_async( + int32_t camera_id, const Camera::ResultCallback& callback) { - auto cmd_stop_photo_interval = make_command_stop_photo(); + auto cmd_stop_photo_interval = make_command_stop_photo(camera_id); _system_impl->send_command_async( cmd_stop_photo_interval, [this, callback](MavlinkCommandSender::Result result, float) { @@ -814,13 +849,13 @@ void CameraImpl::stop_photo_interval_async(const Camera::ResultCallback& callbac }); } -void CameraImpl::start_video_async(const Camera::ResultCallback& callback) +void CameraImpl::start_video_async(int32_t camera_id, const Camera::ResultCallback& callback) { // TODO: check whether video capture is already in progress. // TODO: check whether we are in video mode. // Capture status rate is not set - auto cmd_start_video = make_command_start_video(0.f); + auto cmd_start_video = make_command_start_video(camera_id, 0.f); _system_impl->send_command_async( cmd_start_video, [this, callback](MavlinkCommandSender::Result result, float) { @@ -828,9 +863,9 @@ void CameraImpl::start_video_async(const Camera::ResultCallback& callback) }); } -void CameraImpl::stop_video_async(const Camera::ResultCallback& callback) +void CameraImpl::stop_video_async(int32_t camera_id, const Camera::ResultCallback& callback) { - auto cmd_stop_video = make_command_stop_video(); + auto cmd_stop_video = make_command_stop_video(camera_id); _system_impl->send_command_async( cmd_stop_video, [this, callback](MavlinkCommandSender::Result result, float) { @@ -838,42 +873,43 @@ void CameraImpl::stop_video_async(const Camera::ResultCallback& callback) }); } -Camera::Information CameraImpl::information() const +Camera::CameraList CameraImpl::camera_list() const { - std::lock_guard lock(_information.mutex); + std::lock_guard lock(_camera_list.mutex); - return _information.data; + return _camera_list.data; } -Camera::InformationHandle -CameraImpl::subscribe_information(const Camera::InformationCallback& callback) +Camera::CameraListHandle +CameraImpl::subscribe_camera_list(const Camera::CameraListCallback& callback) { - std::lock_guard lock(_information.mutex); - auto handle = _information.subscription_callbacks.subscribe(callback); + std::lock_guard lock(_camera_list.mutex); + auto handle = _camera_list.subscription_callbacks.subscribe(callback); // If there was already a subscription, cancel the call if (_status.call_every_cookie) { _system_impl->remove_call_every(_status.call_every_cookie); } - if (callback) { - _system_impl->remove_call_every(_status.call_every_cookie); - _status.call_every_cookie = - _system_impl->add_call_every([this]() { request_status(); }, 1.0); - } else { - _system_impl->remove_call_every(_status.call_every_cookie); - } + // TODO: add again + // if (callback) { + // _system_impl->remove_call_every(_status.call_every_cookie); + // _status.call_every_cookie = + // _system_impl->add_call_every([this]() { request_status(); }, 1.0); + //} else { + // _system_impl->remove_call_every(_status.call_every_cookie); + //} return handle; } -void CameraImpl::unsubscribe_information(Camera::InformationHandle handle) +void CameraImpl::unsubscribe_camera_list(Camera::CameraListHandle handle) { - std::lock_guard lock(_information.mutex); - _information.subscription_callbacks.unsubscribe(handle); + std::lock_guard lock(_camera_list.mutex); + _camera_list.subscription_callbacks.unsubscribe(handle); } -Camera::Result CameraImpl::start_video_streaming(int32_t stream_id) +Camera::Result CameraImpl::start_video_streaming(int32_t camera_id, int32_t stream_id) { std::lock_guard lock(_video_stream_info.mutex); @@ -883,7 +919,7 @@ Camera::Result CameraImpl::start_video_streaming(int32_t stream_id) } // TODO Check whether we're in video mode - auto command = make_command_start_video_streaming(stream_id); + auto command = make_command_start_video_streaming(camera_id, stream_id); auto result = camera_result_from_command_result(_system_impl->send_command(command)); // if (result == Camera::Result::Success) { @@ -894,12 +930,12 @@ Camera::Result CameraImpl::start_video_streaming(int32_t stream_id) return result; } -Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id) +Camera::Result CameraImpl::stop_video_streaming(int32_t camera_id, int32_t stream_id) { // TODO I think we need to maintain current state, whether we issued // video capture request or video streaming request, etc.We shouldn't // send stop video streaming if we've not started it! - auto command = make_command_stop_video_streaming(stream_id); + auto command = make_command_stop_video_streaming(camera_id, stream_id); auto result = camera_result_from_command_result(_system_impl->send_command(command)); { @@ -910,12 +946,12 @@ Camera::Result CameraImpl::stop_video_streaming(int32_t stream_id) return result; } -void CameraImpl::request_video_stream_info() +void CameraImpl::request_video_stream_info(int32_t camera_id) { _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, component_id_for_camera_id(camera_id), nullptr); _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, component_id_for_camera_id(camera_id), nullptr); } Camera::VideoStreamInfo CameraImpl::video_stream_info() @@ -932,13 +968,15 @@ CameraImpl::subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& c auto handle = _video_stream_info.subscription_callbacks.subscribe(callback); + /* TODO: request for all if (callback) { _system_impl->remove_call_every(_video_stream_info.call_every_cookie); _video_stream_info.call_every_cookie = - _system_impl->add_call_every([this]() { request_video_stream_info(); }, 1.0); + _system_impl->add_call_every([this]() { request_video_stream_info(camera_id); }, 1.0); } else { _system_impl->remove_call_every(_video_stream_info.call_every_cookie); } + */ return handle; } @@ -1001,10 +1039,10 @@ Camera::Result CameraImpl::camera_result_from_parameter_result( } } -Camera::Result CameraImpl::set_mode(const Camera::Mode mode) +Camera::Result CameraImpl::set_mode(int32_t camera_id, const Camera::Mode mode) { const float mavlink_mode = to_mavlink_camera_mode(mode); - auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode); + auto cmd_set_camera_mode = make_command_set_camera_mode(camera_id, mavlink_mode); const auto command_result = _system_impl->send_command(cmd_set_camera_mode); const auto camera_result = camera_result_from_command_result(command_result); @@ -1083,10 +1121,11 @@ float CameraImpl::to_mavlink_camera_mode(const Camera::Mode mode) const } } -void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback) +void CameraImpl::set_mode_async( + int32_t camera_id, const Camera::Mode mode, const Camera::ResultCallback& callback) { const auto mavlink_mode = to_mavlink_camera_mode(mode); - auto cmd_set_camera_mode = make_command_set_camera_mode(mavlink_mode); + auto cmd_set_camera_mode = make_command_set_camera_mode(camera_id, mavlink_mode); _system_impl->send_command_async( cmd_set_camera_mode, @@ -1096,12 +1135,6 @@ void CameraImpl::set_mode_async(const Camera::Mode mode, const Camera::ResultCal }); } -Camera::Mode CameraImpl::mode() -{ - std::lock_guard lock(_mode.mutex); - return _mode.data; -} - Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callback) { std::unique_lock lock(_mode.mutex); @@ -1110,6 +1143,7 @@ Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callba notify_mode(); + /* TODO: implement for all if (callback) { _system_impl->remove_call_every(_mode.call_every_cookie); _mode.call_every_cookie = @@ -1117,6 +1151,7 @@ Camera::ModeHandle CameraImpl::subscribe_mode(const Camera::ModeCallback& callba } else { _system_impl->remove_call_every(_mode.call_every_cookie); } + */ return handle; } @@ -1138,12 +1173,12 @@ bool CameraImpl::interval_valid(float interval_s) } } -void CameraImpl::request_status() +void CameraImpl::request_status(int32_t camera_id) { _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, component_id_for_camera_id(camera_id), nullptr); _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_STORAGE_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_STORAGE_INFORMATION, component_id_for_camera_id(camera_id), nullptr); } Camera::StatusHandle CameraImpl::subscribe_status(const Camera::StatusCallback& callback) @@ -1160,12 +1195,6 @@ void CameraImpl::unsubscribe_status(Camera::StatusHandle handle) _status.subscription_callbacks.unsubscribe(handle); } -Camera::Status CameraImpl::status() -{ - std::lock_guard lock(_status.mutex); - return _status.data; -} - Camera::CaptureInfoHandle CameraImpl::subscribe_capture_info(const Camera::CaptureInfoCallback& callback) { @@ -1179,6 +1208,36 @@ void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle) _capture_info.callbacks.unsubscribe(handle); } +void CameraImpl::process_heartbeat(const mavlink_message_t& message) +{ + // Check for potential camera + std::unique_lock lock(_potential_cameras_mutex); + auto found = + std::any_of(_potential_cameras.begin(), _potential_cameras.end(), [&](const auto& item) { + return item.component_id == message.compid; + }); + + if (!found) { + auto new_potential_camera = PotentialCamera{}; + new_potential_camera.component_id = message.compid; + _potential_cameras.emplace_back(std::move(new_potential_camera)); + check_potential_cameras(); + } +} + +void CameraImpl::check_potential_cameras() +{ + std::lock_guard lock(_potential_cameras_mutex); + + for (auto& potential_camera : _potential_cameras) { + // First step, get information if we don't already have it. + if (!potential_camera.maybe_information) { + request_camera_information(potential_camera.component_id); + potential_camera.information_requested = true; + } + } +} + void CameraImpl::process_camera_capture_status(const mavlink_message_t& message) { mavlink_camera_capture_status_t camera_capture_status; @@ -1351,6 +1410,7 @@ void CameraImpl::request_missing_capture_info() } } + /* TODO: implement again if (!_capture_info.missing_image_retries.empty()) { auto it_lowest_retries = std::min_element( _capture_info.missing_image_retries.begin(), _capture_info.missing_image_retries.end()); @@ -1361,6 +1421,7 @@ void CameraImpl::request_missing_capture_info() it_lowest_retries->first); it_lowest_retries->second += 1; } + */ } Camera::EulerAngle CameraImpl::to_euler_angle_from_quaternion(Camera::Quaternion quaternion) @@ -1417,18 +1478,47 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) camera_information.model_name[sizeof(camera_information.model_name) - 1] = '\0'; camera_information.cam_definition_uri[sizeof(camera_information.cam_definition_uri) - 1] = '\0'; - std::lock_guard lock(_information.mutex); + Camera::Information new_information{}; + new_information.vendor_name = reinterpret_cast(camera_information.vendor_name); + new_information.focal_length_mm = camera_information.focal_length; + + std::lock_guard lock(_potential_cameras_mutex); + + auto potential_camera = + std::find_if(_potential_cameras.begin(), _potential_cameras.end(), [&](auto& item) { + return item.component_id == message.compid; + }); + + if (potential_camera == _potential_cameras.end()) { + auto new_potential_camera = PotentialCamera{}; + new_potential_camera.component_id = message.compid; + new_potential_camera.maybe_information = new_information; + _potential_cameras.emplace_back(std::move(new_potential_camera)); + } else { + potential_camera->maybe_information = new_information; + } + + /* TODO: fixup + _camera_list.data.vendor_name = (char*)(camera_information.vendor_name); + _camera_list.data.model_name = (char*)(camera_information.model_name); + _camera_list.data.focal_length_mm = camera_information.focal_length; + _camera_list.data.horizontal_sensor_size_mm = camera_information.sensor_size_h; + _camera_list.data.vertical_sensor_size_mm = camera_information.sensor_size_v; + _camera_list.data.horizontal_resolution_px = camera_information.resolution_h; + _camera_list.data.vertical_resolution_px = camera_information.resolution_v; + */ - _information.data.vendor_name = (char*)(camera_information.vendor_name); - _information.data.model_name = (char*)(camera_information.model_name); - _information.data.focal_length_mm = camera_information.focal_length; - _information.data.horizontal_sensor_size_mm = camera_information.sensor_size_h; - _information.data.vertical_sensor_size_mm = camera_information.sensor_size_v; - _information.data.horizontal_resolution_px = camera_information.resolution_h; - _information.data.vertical_resolution_px = camera_information.resolution_v; +#if 0 + _camera_list.subscription_callbacks.queue( + _camera_list.data, [this](const auto& func) { _system_impl->call_user_callback(func); }); + + if (potential_camera.maybe_information && potential_camera.maybe_information.value().model_name) {} + _system_impl->mavlink_ftp_client().download_async( + download_path, + tmp_download_path.string(), + true, + [this, &component, local_path, compid, type, file_cache_tag]( - _information.subscription_callbacks.queue( - _information.data, [this](const auto& func) { _system_impl->call_user_callback(func); }); if (should_fetch_camera_definition(camera_information.cam_definition_uri)) { _is_fetching_camera_definition = true; @@ -1477,6 +1567,7 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) _is_fetching_camera_definition = false; }).detach(); } +#endif } bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const @@ -1727,10 +1818,10 @@ void CameraImpl::receive_set_mode_command_result( void CameraImpl::notify_mode() { - std::lock_guard lock(_mode.mutex); + // std::lock_guard lock(_mode.mutex); - _mode.subscription_callbacks.queue( - _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); }); + //_mode.subscription_callbacks.queue( + // _mode.data, [this](const auto& func) { _system_impl->call_user_callback(func); }); } bool CameraImpl::get_possible_setting_options(std::vector& settings) @@ -1791,17 +1882,20 @@ bool CameraImpl::is_setting_range(const std::string& setting_id) return _camera_definition->is_setting_range(setting_id); } -Camera::Result CameraImpl::set_setting(Camera::Setting setting) +Camera::Result CameraImpl::set_setting(int32_t camera_id, Camera::Setting setting) + { auto prom = std::make_shared>(); auto ret = prom->get_future(); - set_setting_async(setting, [&prom](Camera::Result result) { prom->set_value(result); }); + set_setting_async( + camera_id, setting, [&prom](Camera::Result result) { prom->set_value(result); }); return ret.get(); } -void CameraImpl::set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback) +void CameraImpl::set_setting_async( + int32_t camera_id, Camera::Setting setting, const Camera::ResultCallback callback) { set_option_async(setting.setting_id, setting.option, callback); } @@ -1937,7 +2031,7 @@ void CameraImpl::set_option_async( } void CameraImpl::get_setting_async( - Camera::Setting setting, const Camera::GetSettingCallback callback) + int32_t camera_id, Camera::Setting setting, const Camera::GetSettingCallback callback) { get_option_async( setting.setting_id, @@ -1952,14 +2046,16 @@ void CameraImpl::get_setting_async( }); } -std::pair CameraImpl::get_setting(Camera::Setting setting) +std::pair +CameraImpl::get_setting(int32_t camera_id, Camera::Setting setting) { auto prom = std::make_shared>>(); auto ret = prom->get_future(); - get_setting_async(setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) { - prom->set_value(std::make_pair<>(result, new_setting)); - }); + get_setting_async( + camera_id, setting, [&prom](Camera::Result result, const Camera::Setting& new_setting) { + prom->set_value(std::make_pair<>(result, new_setting)); + }); return ret.get(); } @@ -2227,29 +2323,31 @@ bool CameraImpl::get_option_str( return _camera_definition->get_option_str(setting_id, option_id, description); } -void CameraImpl::request_camera_settings() +void CameraImpl::request_camera_settings(int32_t camera_id) { _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_CAMERA_SETTINGS, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_CAMERA_SETTINGS, component_id_for_camera_id(camera_id), nullptr); } -void CameraImpl::request_camera_information() +void CameraImpl::request_camera_information(uint8_t component_id) { _system_impl->mavlink_request_message().request( - MAVLINK_MSG_ID_CAMERA_INFORMATION, _camera_id + MAV_COMP_ID_CAMERA, nullptr); + MAVLINK_MSG_ID_CAMERA_INFORMATION, component_id, nullptr); } -Camera::Result CameraImpl::format_storage(int32_t storage_id) +Camera::Result CameraImpl::format_storage(int32_t camera_id, int32_t storage_id) { auto prom = std::make_shared>(); auto ret = prom->get_future(); - format_storage_async(storage_id, [prom](Camera::Result result) { prom->set_value(result); }); + format_storage_async( + camera_id, storage_id, [prom](Camera::Result result) { prom->set_value(result); }); return ret.get(); } -void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback callback) +void CameraImpl::format_storage_async( + int32_t camera_id, int32_t storage_id, Camera::ResultCallback callback) { MavlinkCommandSender::CommandLong cmd_format{}; @@ -2273,16 +2371,16 @@ void CameraImpl::format_storage_async(int32_t storage_id, Camera::ResultCallback }); } -Camera::Result CameraImpl::reset_settings() +Camera::Result CameraImpl::reset_settings(int32_t camera_id) { auto prom = std::make_shared>(); auto ret = prom->get_future(); - reset_settings_async([prom](Camera::Result result) { prom->set_value(result); }); + reset_settings_async(camera_id, [prom](Camera::Result result) { prom->set_value(result); }); return ret.get(); } -void CameraImpl::reset_settings_async(const Camera::ResultCallback callback) +void CameraImpl::reset_settings_async(int32_t camera_id, const Camera::ResultCallback callback) { MavlinkCommandSender::CommandLong cmd_format{}; @@ -2316,13 +2414,15 @@ void CameraImpl::reset_following_format_storage() } std::pair> -CameraImpl::list_photos(Camera::PhotosRange photos_range) +CameraImpl::list_photos(int32_t camera_id, Camera::PhotosRange photos_range) { std::promise>> prom; auto ret = prom.get_future(); list_photos_async( - photos_range, [&prom](Camera::Result result, std::vector photo_list) { + camera_id, + photos_range, + [&prom](Camera::Result result, std::vector photo_list) { prom.set_value(std::make_pair(result, photo_list)); }); @@ -2330,7 +2430,7 @@ CameraImpl::list_photos(Camera::PhotosRange photos_range) } void CameraImpl::list_photos_async( - Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback) + int32_t camera_id, Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback) { if (!callback) { LogWarn() << "Trying to get a photo list with a null callback, ignoring..."; @@ -2439,4 +2539,10 @@ void CameraImpl::list_photos_async( }).detach(); } +uint8_t CameraImpl::component_id_for_camera_id(int32_t camera_id) +{ + // TODO: implement + return 0; +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index ed435b215c..1481751897 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -23,88 +23,103 @@ class CameraImpl : public PluginImplBase { void enable() override; void disable() override; - Camera::Result prepare(); - Camera::Result select_camera(size_t id); + Camera::Result take_photo(int32_t camera_id); - Camera::Result take_photo(); + Camera::Result start_photo_interval(int32_t camera_id, float interval_s); + Camera::Result stop_photo_interval(int32_t camera_id); - Camera::Result start_photo_interval(float interval_s); - Camera::Result stop_photo_interval(); + Camera::Result start_video(int32_t camera_id); + Camera::Result stop_video(int32_t camera_id); - Camera::Result start_video(); - Camera::Result stop_video(); + Camera::Result zoom_in_start(int32_t camera_id); + Camera::Result zoom_out_start(int32_t camera_id); + Camera::Result zoom_stop(int32_t camera_id); + Camera::Result zoom_range(int32_t camera_id, float range); + + Camera::Result track_point(int32_t camera_id, float point_x, float point_y, float radius); + Camera::Result track_rectangle( + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y); + Camera::Result track_stop(int32_t camera_id); + Camera::Result focus_in_start(int32_t camera_id); + Camera::Result focus_out_start(int32_t camera_id); + Camera::Result focus_stop(int32_t camera_id); + Camera::Result focus_range(int32_t camera_id, float range); + + void zoom_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback); + void zoom_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback); + void zoom_stop_async(int32_t camera_id, const Camera::ResultCallback& callback); + void zoom_range_async(int32_t camera_id, float range, const Camera::ResultCallback& callback); - Camera::Result zoom_in_start(); - Camera::Result zoom_out_start(); - Camera::Result zoom_stop(); - Camera::Result zoom_range(float range); - Camera::Result track_point(float point_x, float point_y, float radius); - Camera::Result - track_rectangle(float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y); - Camera::Result track_stop(); - Camera::Result focus_in_start(); - Camera::Result focus_out_start(); - Camera::Result focus_stop(); - Camera::Result focus_range(float range); - - void zoom_in_start_async(const Camera::ResultCallback& callback); - void zoom_out_start_async(const Camera::ResultCallback& callback); - void zoom_stop_async(const Camera::ResultCallback& callback); - void zoom_range_async(float range, const Camera::ResultCallback& callback); void track_point_async( - float point_x, float point_y, float radius, const Camera::ResultCallback& callback); + int32_t camera_id, + float point_x, + float point_y, + float radius, + const Camera::ResultCallback& callback); void track_rectangle_async( + int32_t camera_id, float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y, const Camera::ResultCallback& callback); - void track_stop_async(const Camera::ResultCallback& callback); - void focus_in_start_async(const Camera::ResultCallback& callback); - void focus_out_start_async(const Camera::ResultCallback& callback); - void focus_stop_async(const Camera::ResultCallback& callback); - void focus_range_async(float range, const Camera::ResultCallback& callback); + void track_stop_async(int32_t camera_id, const Camera::ResultCallback& callback); - void prepare_async(const Camera::ResultCallback& callback); - void take_photo_async(const Camera::ResultCallback& callback); - void start_photo_interval_async(float interval_s, const Camera::ResultCallback& callback); - void stop_photo_interval_async(const Camera::ResultCallback& callback); - void start_video_async(const Camera::ResultCallback& callback); - void stop_video_async(const Camera::ResultCallback& callback); + void focus_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback); + void focus_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback); + void focus_stop_async(int32_t camera_id, const Camera::ResultCallback& callback); + void focus_range_async(int32_t camera_id, float range, const Camera::ResultCallback& callback); - Camera::Information information() const; - Camera::InformationHandle subscribe_information(const Camera::InformationCallback& callback); - void unsubscribe_information(Camera::InformationHandle handle); + void take_photo_async(int32_t camera_id, const Camera::ResultCallback& callback); + void start_photo_interval_async( + int32_t camera_id, float interval_s, const Camera::ResultCallback& callback); + void stop_photo_interval_async(int32_t camera_id, const Camera::ResultCallback& callback); + void start_video_async(int32_t camera_id, const Camera::ResultCallback& callback); + void stop_video_async(int32_t camera_id, const Camera::ResultCallback& callback); - std::pair get_video_stream_info(); + Camera::CameraList camera_list() const; + Camera::CameraListHandle subscribe_camera_list(const Camera::CameraListCallback& callback); + void unsubscribe_camera_list(Camera::CameraListHandle handle); Camera::VideoStreamInfo video_stream_info(); Camera::VideoStreamInfoHandle subscribe_video_stream_info(const Camera::VideoStreamInfoCallback& callback); void unsubscribe_video_stream_info(Camera::VideoStreamInfoHandle handle); - Camera::Result start_video_streaming(int32_t stream_id); - Camera::Result stop_video_streaming(int32_t stream_id); + Camera::VideoStreamInfo get_video_stream_info(int32_t camera_id); + + Camera::Result start_video_streaming(int32_t camera_id, int32_t stream_id); + Camera::Result stop_video_streaming(int32_t camera_id, int32_t stream_id); + + Camera::Result set_mode(int32_t camera_id, const Camera::Mode mode); + void set_mode_async( + int32_t camera_id, const Camera::Mode mode, const Camera::ResultCallback& callback); - Camera::Result set_mode(const Camera::Mode mode); - void set_mode_async(const Camera::Mode mode, const Camera::ResultCallback& callback); + Camera::Mode get_mode(int32_t camera_id); - Camera::Mode mode(); Camera::ModeHandle subscribe_mode(const Camera::ModeCallback& callback); void unsubscribe_mode(Camera::ModeHandle handle); Camera::CaptureInfoHandle subscribe_capture_info(const Camera::CaptureInfoCallback& callback); void unsubscribe_capture_info(Camera::CaptureInfoHandle handle); - Camera::Status status(); Camera::StatusHandle subscribe_status(const Camera::StatusCallback& callback); void unsubscribe_status(Camera::StatusHandle handle); - Camera::Result set_setting(Camera::Setting setting); - void set_setting_async(Camera::Setting setting, const Camera::ResultCallback callback); + Camera::Status get_status(int32_t camera_id); - void get_setting_async(Camera::Setting setting, const Camera::GetSettingCallback callback); - std::pair get_setting(Camera::Setting setting); + Camera::Result set_setting(int32_t camera_id, Camera::Setting setting); + void set_setting_async( + int32_t camera_id, Camera::Setting setting, const Camera::ResultCallback callback); + + void get_setting_async( + int32_t camera_id, Camera::Setting setting, const Camera::GetSettingCallback callback); + std::pair + get_setting(int32_t camera_id, Camera::Setting setting); std::vector possible_setting_options(); @@ -113,20 +128,29 @@ class CameraImpl : public PluginImplBase { Camera::CurrentSettingsHandle subscribe_current_settings(const Camera::CurrentSettingsCallback& callback); void unsubscribe_current_settings(Camera::CurrentSettingsHandle handle); + + std::pair> get_current_settings(int32_t camera_id); + Camera::PossibleSettingOptionsHandle subscribe_possible_setting_options(const Camera::PossibleSettingOptionsCallback& callback); void unsubscribe_possible_setting_options(Camera::PossibleSettingOptionsHandle handle); - Camera::Result format_storage(int32_t storage_id); - void format_storage_async(int32_t storage_id, const Camera::ResultCallback callback); + std::pair> + get_possible_setting_options(int32_t camera_id); + + Camera::Result format_storage(int32_t camera_id, int32_t storage_id); + void format_storage_async( + int32_t camera_id, int32_t storage_id, const Camera::ResultCallback callback); - Camera::Result reset_settings(); - void reset_settings_async(const Camera::ResultCallback callback); + Camera::Result reset_settings(int32_t camera_id); + void reset_settings_async(int32_t camera_id, const Camera::ResultCallback callback); std::pair> - list_photos(Camera::PhotosRange photos_range); - void - list_photos_async(Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback); + list_photos(int32_t camera_id, Camera::PhotosRange photos_range); + void list_photos_async( + int32_t camera_id, + Camera::PhotosRange photos_range, + const Camera::ListPhotosCallback callback); CameraImpl(const CameraImpl&) = delete; CameraImpl& operator=(const CameraImpl&) = delete; @@ -149,11 +173,6 @@ class CameraImpl : public PluginImplBase { bool get_option_str( const std::string& setting_id, const std::string& option_id, std::string& description); - void check_connection_status(); - void manual_enable(); - void manual_disable(); - void update_component(); - void receive_set_mode_command_result( const MavlinkCommandSender::Result command_result, const Camera::ResultCallback callback, @@ -169,6 +188,7 @@ class CameraImpl : public PluginImplBase { static bool interval_valid(float interval_s); + void process_heartbeat(const mavlink_message_t& message); void process_camera_image_captured(const mavlink_message_t& message); void process_storage_information(const mavlink_message_t& message); void process_camera_capture_status(const mavlink_message_t& message); @@ -178,6 +198,8 @@ class CameraImpl : public PluginImplBase { void process_video_stream_status(const mavlink_message_t& message); void reset_following_format_storage(); + void check_potential_cameras(); + Camera::Status::StorageStatus storage_status_from_mavlink(const int storage_status) const; Camera::Status::StorageType storage_type_from_mavlink(const int storage_type) const; @@ -206,45 +228,81 @@ class CameraImpl : public PluginImplBase { Camera::Mode to_camera_mode(const uint8_t mavlink_camera_mode) const; CallEveryHandler::Cookie _camera_information_call_every_cookie{}; - CallEveryHandler::Cookie _check_connection_status_call_every_cookie{}; CallEveryHandler::Cookie _request_missing_capture_info_cookie{}; - void request_camera_settings(); - void request_camera_information(); - void request_video_stream_info(); - void request_video_stream_status(); - void request_status(); + void request_camera_settings(int32_t camera_id); + void request_camera_information(uint8_t component_id); + void request_video_stream_info(int32_t camera_id); + void request_video_stream_status(int32_t camera_id); + void request_status(int32_t camera_id); + + MavlinkCommandSender::CommandLong + make_command_take_photo(int32_t camera_id, float interval_s, float no_of_photos); + MavlinkCommandSender::CommandLong make_command_stop_photo(int32_t camera_id); - MavlinkCommandSender::CommandLong make_command_take_photo(float interval_s, float no_of_photos); - MavlinkCommandSender::CommandLong make_command_stop_photo(); + MavlinkCommandSender::CommandLong make_command_request_camera_info(int32_t camera_id); + MavlinkCommandSender::CommandLong + make_command_set_camera_mode(int32_t camera_id, float mavlink_mode); + MavlinkCommandSender::CommandLong make_command_request_camera_settings(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_request_camera_capture_status(int32_t camera_id); + MavlinkCommandSender::CommandLong + make_command_request_camera_image_captured(int32_t camera_id, size_t photo_id); + MavlinkCommandSender::CommandLong make_command_request_storage_info(int32_t camera_id); - MavlinkCommandSender::CommandLong make_command_set_camera_mode(float mavlink_mode); - MavlinkCommandSender::CommandLong make_command_start_video(float capture_status_rate_hz); - MavlinkCommandSender::CommandLong make_command_stop_video(); + MavlinkCommandSender::CommandLong + make_command_start_video(int32_t camera_id, float capture_status_rate_hz); + MavlinkCommandSender::CommandLong make_command_stop_video(int32_t camera_id); - MavlinkCommandSender::CommandLong make_command_start_video_streaming(int32_t stream_id); - MavlinkCommandSender::CommandLong make_command_stop_video_streaming(int32_t stream_id); + MavlinkCommandSender::CommandLong + make_command_start_video_streaming(int32_t camera_id, int32_t stream_id); + MavlinkCommandSender::CommandLong + make_command_stop_video_streaming(int32_t camera_id, int32_t stream_id); - MavlinkCommandSender::CommandLong make_command_zoom_in(); - MavlinkCommandSender::CommandLong make_command_zoom_out(); - MavlinkCommandSender::CommandLong make_command_zoom_stop(); - MavlinkCommandSender::CommandLong make_command_zoom_range(float range); + MavlinkCommandSender::CommandLong make_command_zoom_in(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_zoom_out(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_zoom_stop(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_zoom_range(int32_t camera_id, float range); MavlinkCommandSender::CommandLong - make_command_track_point(float point_x, float point_y, float radius); + make_command_track_point(int32_t camera_id, float point_x, float point_y, float radius); MavlinkCommandSender::CommandLong make_command_track_rectangle( - float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y); - MavlinkCommandSender::CommandLong make_command_track_stop(); - MavlinkCommandSender::CommandLong make_command_focus_in(); - MavlinkCommandSender::CommandLong make_command_focus_out(); - MavlinkCommandSender::CommandLong make_command_focus_stop(); - MavlinkCommandSender::CommandLong make_command_focus_range(float range); + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y); + MavlinkCommandSender::CommandLong make_command_track_stop(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_focus_in(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_focus_out(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_focus_stop(int32_t camera_id); + MavlinkCommandSender::CommandLong make_command_focus_range(int32_t camera_id, float range); void request_missing_capture_info(); + uint8_t component_id_for_camera_id(int32_t camera_id); + static bool starts_with(const std::string& str, const std::string& prefix); static std::string get_filename_from_path(const std::string& path); static std::string strip_mavlinkftp_prefix(const std::string& str); + struct PotentialCamera { + std::optional maybe_information; + + std::unique_ptr _camera_definition{}; + bool _is_fetching_camera_definition{false}; + bool _has_camera_definition_timed_out{false}; + size_t _camera_definition_fetch_count{0}; + using CameraDefinitionCallback = std::function; + CameraDefinitionCallback _camera_definition_callback{}; + + bool information_requested{false}; + uint8_t component_id; + }; + + std::mutex _potential_cameras_mutex; + std::vector _potential_cameras; + + CallEveryHandler::Cookie _check_potential_cameras_call_every_cookie{}; + std::unique_ptr _camera_definition{}; bool _is_fetching_camera_definition{false}; bool _has_camera_definition_timed_out{false}; @@ -274,7 +332,7 @@ class CameraImpl : public PluginImplBase { struct { std::mutex mutex{}; Camera::Mode data{}; - CallbackList subscription_callbacks{}; + CallbackList subscription_callbacks{}; CallEveryHandler::Cookie call_every_cookie{}; } _mode{}; @@ -300,9 +358,9 @@ class CameraImpl : public PluginImplBase { struct { mutable std::mutex mutex{}; - Camera::Information data{}; - CallbackList subscription_callbacks{}; - } _information{}; + Camera::CameraList data{}; + CallbackList subscription_callbacks{}; + } _camera_list{}; struct { std::mutex mutex{}; diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 27b6bc68e0..1494a32670 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -95,6 +95,28 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::PhotosRange const& photos_range); + /** + * @brief + */ + struct ModeInfo { + int32_t camera_id{}; /**< @brief Camera ID */ + Mode mode{}; /**< @brief Camera mode */ + }; + + /** + * @brief Equal operator to compare two `Camera::ModeInfo` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const Camera::ModeInfo& lhs, const Camera::ModeInfo& rhs); + + /** + * @brief Stream operator to print information about a `Camera::ModeInfo`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Camera::ModeInfo const& mode_info); + /** * @brief Possible results returned for camera commands */ @@ -298,6 +320,7 @@ class Camera : public PluginBase { std::ostream& str, Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum); + int32_t camera_id{}; /**< @brief Camera ID */ VideoStreamSettings settings{}; /**< @brief Video stream settings */ VideoStreamStatus status{}; /**< @brief Current status of video streaming */ VideoStreamSpectrum spectrum{}; /**< @brief Light-spectrum of the video stream */ @@ -361,6 +384,7 @@ class Camera : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Camera::Status::StorageType const& storage_type); + int32_t camera_id{}; /**< @brief Camera ID */ bool video_on{}; /**< @brief Whether video recording is currently in process */ bool photo_interval_on{}; /**< @brief Whether a photo interval is currently in process */ float used_storage_mib{}; /**< @brief Used storage (in MiB) */ @@ -441,6 +465,7 @@ class Camera : public PluginBase { * @brief Type to represent a setting with a list of options to choose from. */ struct SettingOptions { + int32_t camera_id{}; /**< @brief Camera ID */ std::string setting_id{}; /**< @brief Name of the setting (machine readable) */ std::string setting_description{}; /**< @brief Description of the setting (human readable) */ @@ -492,32 +517,37 @@ class Camera : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Camera::Information const& information); /** - * @brief Callback type for asynchronous Camera calls. + * @brief Camera list */ - using ResultCallback = std::function; + struct CameraList { + std::vector cameras{}; /**< @brief Camera items. */ + }; /** - * @brief Prepare the camera plugin (e.g. download the camera definition, etc). + * @brief Equal operator to compare two `Camera::CameraList` objects. * - * This function is non-blocking. See 'prepare' for the blocking counterpart. + * @return `true` if items are equal. */ - void prepare_async(const ResultCallback callback); + friend bool operator==(const Camera::CameraList& lhs, const Camera::CameraList& rhs); /** - * @brief Prepare the camera plugin (e.g. download the camera definition, etc). + * @brief Stream operator to print information about a `Camera::CameraList`. * - * This function is blocking. See 'prepare_async' for the non-blocking counterpart. - * - * @return Result of request. + * @return A reference to the stream. */ - Result prepare() const; + friend std::ostream& operator<<(std::ostream& str, Camera::CameraList const& camera_list); + + /** + * @brief Callback type for asynchronous Camera calls. + */ + using ResultCallback = std::function; /** * @brief Take one photo. * * This function is non-blocking. See 'take_photo' for the blocking counterpart. */ - void take_photo_async(const ResultCallback callback); + void take_photo_async(int32_t camera_id, const ResultCallback callback); /** * @brief Take one photo. @@ -526,14 +556,15 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result take_photo() const; + Result take_photo(int32_t camera_id) const; /** * @brief Start photo timelapse with a given interval. * * This function is non-blocking. See 'start_photo_interval' for the blocking counterpart. */ - void start_photo_interval_async(float interval_s, const ResultCallback callback); + void + start_photo_interval_async(int32_t camera_id, float interval_s, const ResultCallback callback); /** * @brief Start photo timelapse with a given interval. @@ -542,14 +573,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result start_photo_interval(float interval_s) const; + Result start_photo_interval(int32_t camera_id, float interval_s) const; /** * @brief Stop a running photo timelapse. * * This function is non-blocking. See 'stop_photo_interval' for the blocking counterpart. */ - void stop_photo_interval_async(const ResultCallback callback); + void stop_photo_interval_async(int32_t camera_id, const ResultCallback callback); /** * @brief Stop a running photo timelapse. @@ -558,14 +589,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result stop_photo_interval() const; + Result stop_photo_interval(int32_t camera_id) const; /** * @brief Start a video recording. * * This function is non-blocking. See 'start_video' for the blocking counterpart. */ - void start_video_async(const ResultCallback callback); + void start_video_async(int32_t camera_id, const ResultCallback callback); /** * @brief Start a video recording. @@ -574,14 +605,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result start_video() const; + Result start_video(int32_t camera_id) const; /** * @brief Stop a running video recording. * * This function is non-blocking. See 'stop_video' for the blocking counterpart. */ - void stop_video_async(const ResultCallback callback); + void stop_video_async(int32_t camera_id, const ResultCallback callback); /** * @brief Stop a running video recording. @@ -590,7 +621,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result stop_video() const; + Result stop_video(int32_t camera_id) const; /** * @brief Start video streaming. @@ -599,7 +630,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result start_video_streaming(int32_t stream_id) const; + Result start_video_streaming(int32_t camera_id, int32_t stream_id) const; /** * @brief Stop current video streaming. @@ -608,14 +639,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result stop_video_streaming(int32_t stream_id) const; + Result stop_video_streaming(int32_t camera_id, int32_t stream_id) const; /** * @brief Set camera mode. * * This function is non-blocking. See 'set_mode' for the blocking counterpart. */ - void set_mode_async(Mode mode, const ResultCallback callback); + void set_mode_async(int32_t camera_id, Mode mode, const ResultCallback callback); /** * @brief Set camera mode. @@ -624,7 +655,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result set_mode(Mode mode) const; + Result set_mode(int32_t camera_id, Mode mode) const; /** * @brief Callback type for list_photos_async. @@ -636,7 +667,8 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'list_photos' for the blocking counterpart. */ - void list_photos_async(PhotosRange photos_range, const ListPhotosCallback callback); + void list_photos_async( + int32_t camera_id, PhotosRange photos_range, const ListPhotosCallback callback); /** * @brief List photos available on the camera. @@ -645,61 +677,67 @@ class Camera : public PluginBase { * * @return Result of request. */ - std::pair> list_photos(PhotosRange photos_range) const; + std::pair> + list_photos(int32_t camera_id, PhotosRange photos_range) const; /** - * @brief Callback type for subscribe_mode. + * @brief Callback type for subscribe_camera_list. */ - using ModeCallback = std::function; + using CameraListCallback = std::function; /** - * @brief Handle type for subscribe_mode. + * @brief Handle type for subscribe_camera_list. */ - using ModeHandle = Handle; + using CameraListHandle = Handle; /** - * @brief Subscribe to camera mode updates. + * @brief Subscribe to list of cameras. + * + * This allows to find out what cameras are connected to the system. + * Based on the camera ID, we can then address a specific camera. */ - ModeHandle subscribe_mode(const ModeCallback& callback); + CameraListHandle subscribe_camera_list(const CameraListCallback& callback); /** - * @brief Unsubscribe from subscribe_mode + * @brief Unsubscribe from subscribe_camera_list */ - void unsubscribe_mode(ModeHandle handle); + void unsubscribe_camera_list(CameraListHandle handle); /** - * @brief Poll for 'Mode' (blocking). + * @brief Poll for 'CameraList' (blocking). * - * @return One Mode update. + * @return One CameraList update. */ - Mode mode() const; + CameraList camera_list() const; /** - * @brief Callback type for subscribe_information. + * @brief Callback type for subscribe_mode. */ - using InformationCallback = std::function; + using ModeCallback = std::function; /** - * @brief Handle type for subscribe_information. + * @brief Handle type for subscribe_mode. */ - using InformationHandle = Handle; + using ModeHandle = Handle; /** - * @brief Subscribe to camera information updates. + * @brief Subscribe to camera mode updates. */ - InformationHandle subscribe_information(const InformationCallback& callback); + ModeHandle subscribe_mode(const ModeCallback& callback); /** - * @brief Unsubscribe from subscribe_information + * @brief Unsubscribe from subscribe_mode */ - void unsubscribe_information(InformationHandle handle); + void unsubscribe_mode(ModeHandle handle); /** - * @brief Poll for 'Information' (blocking). + * @brief Get camera mode. * - * @return One Information update. + * This function is blocking. + * + * @return Result of request. */ - Information information() const; + Camera::Mode get_mode(int32_t camera_id) const; /** * @brief Callback type for subscribe_video_stream_info. @@ -722,11 +760,13 @@ class Camera : public PluginBase { void unsubscribe_video_stream_info(VideoStreamInfoHandle handle); /** - * @brief Poll for 'VideoStreamInfo' (blocking). + * @brief Get video stream info. + * + * This function is blocking. * - * @return One VideoStreamInfo update. + * @return Result of request. */ - VideoStreamInfo video_stream_info() const; + Camera::VideoStreamInfo get_video_stream_info(int32_t camera_id) const; /** * @brief Callback type for subscribe_capture_info. @@ -769,11 +809,13 @@ class Camera : public PluginBase { void unsubscribe_status(StatusHandle handle); /** - * @brief Poll for 'Status' (blocking). + * @brief Get camera status. + * + * This function is blocking. * - * @return One Status update. + * @return Result of request. */ - Status status() const; + Camera::Status get_status(int32_t camera_id) const; /** * @brief Callback type for subscribe_current_settings. @@ -795,6 +837,15 @@ class Camera : public PluginBase { */ void unsubscribe_current_settings(CurrentSettingsHandle handle); + /** + * @brief Get current settings. + * + * This function is blocking. + * + * @return Result of request. + */ + std::pair> get_current_settings(int32_t camera_id) const; + /** * @brief Callback type for subscribe_possible_setting_options. */ @@ -817,11 +868,14 @@ class Camera : public PluginBase { void unsubscribe_possible_setting_options(PossibleSettingOptionsHandle handle); /** - * @brief Poll for 'std::vector' (blocking). + * @brief Get possible setting options. * - * @return One std::vector update. + * This function is blocking. + * + * @return Result of request. */ - std::vector possible_setting_options() const; + std::pair> + get_possible_setting_options(int32_t camera_id) const; /** * @brief Set a setting to some value. @@ -830,7 +884,7 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'set_setting' for the blocking counterpart. */ - void set_setting_async(Setting setting, const ResultCallback callback); + void set_setting_async(int32_t camera_id, Setting setting, const ResultCallback callback); /** * @brief Set a setting to some value. @@ -841,7 +895,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result set_setting(Setting setting) const; + Result set_setting(int32_t camera_id, Setting setting) const; /** * @brief Callback type for get_setting_async. @@ -855,7 +909,7 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'get_setting' for the blocking counterpart. */ - void get_setting_async(Setting setting, const GetSettingCallback callback); + void get_setting_async(int32_t camera_id, Setting setting, const GetSettingCallback callback); /** * @brief Get a setting. @@ -866,7 +920,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - std::pair get_setting(Setting setting) const; + std::pair get_setting(int32_t camera_id, Setting setting) const; /** * @brief Format storage (e.g. SD card) in camera. @@ -875,7 +929,7 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'format_storage' for the blocking counterpart. */ - void format_storage_async(int32_t storage_id, const ResultCallback callback); + void format_storage_async(int32_t camera_id, int32_t storage_id, const ResultCallback callback); /** * @brief Format storage (e.g. SD card) in camera. @@ -886,18 +940,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result format_storage(int32_t storage_id) const; - - /** - * @brief Select current camera . - * - * Bind the plugin instance to a specific camera_id - * - * This function is blocking. - * - * @return Result of request. - */ - Result select_camera(int32_t camera_id) const; + Result format_storage(int32_t camera_id, int32_t storage_id) const; /** * @brief Reset all settings in camera. @@ -906,7 +949,7 @@ class Camera : public PluginBase { * * This function is non-blocking. See 'reset_settings' for the blocking counterpart. */ - void reset_settings_async(const ResultCallback callback); + void reset_settings_async(int32_t camera_id, const ResultCallback callback); /** * @brief Reset all settings in camera. @@ -917,14 +960,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result reset_settings() const; + Result reset_settings(int32_t camera_id) const; /** * @brief Start zooming in. * * This function is non-blocking. See 'zoom_in_start' for the blocking counterpart. */ - void zoom_in_start_async(const ResultCallback callback); + void zoom_in_start_async(int32_t camera_id, const ResultCallback callback); /** * @brief Start zooming in. @@ -933,14 +976,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result zoom_in_start() const; + Result zoom_in_start(int32_t camera_id) const; /** * @brief Start zooming out. * * This function is non-blocking. See 'zoom_out_start' for the blocking counterpart. */ - void zoom_out_start_async(const ResultCallback callback); + void zoom_out_start_async(int32_t camera_id, const ResultCallback callback); /** * @brief Start zooming out. @@ -949,14 +992,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result zoom_out_start() const; + Result zoom_out_start(int32_t camera_id) const; /** * @brief Stop zooming. * * This function is non-blocking. See 'zoom_stop' for the blocking counterpart. */ - void zoom_stop_async(const ResultCallback callback); + void zoom_stop_async(int32_t camera_id, const ResultCallback callback); /** * @brief Stop zooming. @@ -965,14 +1008,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result zoom_stop() const; + Result zoom_stop(int32_t camera_id) const; /** * @brief Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). * * This function is non-blocking. See 'zoom_range' for the blocking counterpart. */ - void zoom_range_async(float range, const ResultCallback callback); + void zoom_range_async(int32_t camera_id, float range, const ResultCallback callback); /** * @brief Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). @@ -981,15 +1024,19 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result zoom_range(float range) const; + Result zoom_range(int32_t camera_id, float range) const; /** * @brief Track point. * * This function is non-blocking. See 'track_point' for the blocking counterpart. */ - void - track_point_async(float point_x, float point_y, float radius, const ResultCallback callback); + void track_point_async( + int32_t camera_id, + float point_x, + float point_y, + float radius, + const ResultCallback callback); /** * @brief Track point. @@ -998,7 +1045,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result track_point(float point_x, float point_y, float radius) const; + Result track_point(int32_t camera_id, float point_x, float point_y, float radius) const; /** * @brief Track rectangle. @@ -1006,6 +1053,7 @@ class Camera : public PluginBase { * This function is non-blocking. See 'track_rectangle' for the blocking counterpart. */ void track_rectangle_async( + int32_t camera_id, float top_left_x, float top_left_y, float bottom_right_x, @@ -1020,14 +1068,18 @@ class Camera : public PluginBase { * @return Result of request. */ Result track_rectangle( - float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const; + int32_t camera_id, + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y) const; /** * @brief Stop tracking. * * This function is non-blocking. See 'track_stop' for the blocking counterpart. */ - void track_stop_async(const ResultCallback callback); + void track_stop_async(int32_t camera_id, const ResultCallback callback); /** * @brief Stop tracking. @@ -1036,14 +1088,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result track_stop() const; + Result track_stop(int32_t camera_id) const; /** * @brief Start focusing in. * * This function is non-blocking. See 'focus_in_start' for the blocking counterpart. */ - void focus_in_start_async(const ResultCallback callback); + void focus_in_start_async(int32_t camera_id, const ResultCallback callback); /** * @brief Start focusing in. @@ -1052,14 +1104,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result focus_in_start() const; + Result focus_in_start(int32_t camera_id) const; /** * @brief Start focusing out. * * This function is non-blocking. See 'focus_out_start' for the blocking counterpart. */ - void focus_out_start_async(const ResultCallback callback); + void focus_out_start_async(int32_t camera_id, const ResultCallback callback); /** * @brief Start focusing out. @@ -1068,14 +1120,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result focus_out_start() const; + Result focus_out_start(int32_t camera_id) const; /** * @brief Stop focus. * * This function is non-blocking. See 'focus_stop' for the blocking counterpart. */ - void focus_stop_async(const ResultCallback callback); + void focus_stop_async(int32_t camera_id, const ResultCallback callback); /** * @brief Stop focus. @@ -1084,14 +1136,14 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result focus_stop() const; + Result focus_stop(int32_t camera_id) const; /** * @brief Focus with range value of full range (value between 0.0 and 100.0). * * This function is non-blocking. See 'focus_range' for the blocking counterpart. */ - void focus_range_async(float range, const ResultCallback callback); + void focus_range_async(int32_t camera_id, float range, const ResultCallback callback); /** * @brief Focus with range value of full range (value between 0.0 and 100.0). @@ -1100,7 +1152,7 @@ class Camera : public PluginBase { * * @return Result of request. */ - Result focus_range(float range) const; + Result focus_range(int32_t camera_id, float range) const; /** * @brief Copy constructor. diff --git a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h index 8283074d36..91b34bb272 100644 --- a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h +++ b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h @@ -252,7 +252,7 @@ class Gimbal : public PluginBase { * @brief Gimbal list */ struct GimbalList { - std::vector gimbals{}; /**< @brief Gimbal item. */ + std::vector gimbals{}; /**< @brief Gimbal items. */ }; /** 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 b7106f8131..810333a964 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc @@ -24,7 +24,6 @@ namespace rpc { namespace camera { static const char* CameraService_method_names[] = { - "/mavsdk.rpc.camera.CameraService/Prepare", "/mavsdk.rpc.camera.CameraService/TakePhoto", "/mavsdk.rpc.camera.CameraService/StartPhotoInterval", "/mavsdk.rpc.camera.CameraService/StopPhotoInterval", @@ -34,17 +33,21 @@ static const char* CameraService_method_names[] = { "/mavsdk.rpc.camera.CameraService/StopVideoStreaming", "/mavsdk.rpc.camera.CameraService/SetMode", "/mavsdk.rpc.camera.CameraService/ListPhotos", + "/mavsdk.rpc.camera.CameraService/SubscribeCameraList", "/mavsdk.rpc.camera.CameraService/SubscribeMode", - "/mavsdk.rpc.camera.CameraService/SubscribeInformation", + "/mavsdk.rpc.camera.CameraService/GetMode", "/mavsdk.rpc.camera.CameraService/SubscribeVideoStreamInfo", + "/mavsdk.rpc.camera.CameraService/GetVideoStreamInfo", "/mavsdk.rpc.camera.CameraService/SubscribeCaptureInfo", "/mavsdk.rpc.camera.CameraService/SubscribeStatus", + "/mavsdk.rpc.camera.CameraService/GetStatus", "/mavsdk.rpc.camera.CameraService/SubscribeCurrentSettings", + "/mavsdk.rpc.camera.CameraService/GetCurrentSettings", "/mavsdk.rpc.camera.CameraService/SubscribePossibleSettingOptions", + "/mavsdk.rpc.camera.CameraService/GetPossibleSettingOptions", "/mavsdk.rpc.camera.CameraService/SetSetting", "/mavsdk.rpc.camera.CameraService/GetSetting", "/mavsdk.rpc.camera.CameraService/FormatStorage", - "/mavsdk.rpc.camera.CameraService/SelectCamera", "/mavsdk.rpc.camera.CameraService/ResetSettings", "/mavsdk.rpc.camera.CameraService/ZoomInStart", "/mavsdk.rpc.camera.CameraService/ZoomOutStart", @@ -66,64 +69,44 @@ std::unique_ptr< CameraService::Stub> CameraService::NewStub(const std::shared_p } CameraService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) - : channel_(channel), rpcmethod_Prepare_(CameraService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_TakePhoto_(CameraService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StartPhotoInterval_(CameraService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StopPhotoInterval_(CameraService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StartVideo_(CameraService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StopVideo_(CameraService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StartVideoStreaming_(CameraService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_StopVideoStreaming_(CameraService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetMode_(CameraService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ListPhotos_(CameraService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + : channel_(channel), rpcmethod_TakePhoto_(CameraService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StartPhotoInterval_(CameraService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StopPhotoInterval_(CameraService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StartVideo_(CameraService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StopVideo_(CameraService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StartVideoStreaming_(CameraService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_StopVideoStreaming_(CameraService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetMode_(CameraService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ListPhotos_(CameraService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCameraList_(CameraService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeMode_(CameraService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeInformation_(CameraService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetMode_(CameraService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_SubscribeVideoStreamInfo_(CameraService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCaptureInfo_(CameraService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStatus_(CameraService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCurrentSettings_(CameraService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribePossibleSettingOptions_(CameraService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SetSetting_(CameraService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , 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) - , rpcmethod_ZoomInStart_(CameraService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ZoomOutStart_(CameraService_method_names[23], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ZoomStop_(CameraService_method_names[24], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ZoomRange_(CameraService_method_names[25], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_TrackPoint_(CameraService_method_names[26], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_TrackRectangle_(CameraService_method_names[27], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_TrackStop_(CameraService_method_names[28], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_FocusInStart_(CameraService_method_names[29], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_FocusOutStart_(CameraService_method_names[30], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_FocusStop_(CameraService_method_names[31], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_FocusRange_(CameraService_method_names[32], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_GetVideoStreamInfo_(CameraService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCaptureInfo_(CameraService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStatus_(CameraService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetStatus_(CameraService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeCurrentSettings_(CameraService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetCurrentSettings_(CameraService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribePossibleSettingOptions_(CameraService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetPossibleSettingOptions_(CameraService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetSetting_(CameraService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_GetSetting_(CameraService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_FormatStorage_(CameraService_method_names[23], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ResetSettings_(CameraService_method_names[24], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ZoomInStart_(CameraService_method_names[25], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ZoomOutStart_(CameraService_method_names[26], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ZoomStop_(CameraService_method_names[27], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ZoomRange_(CameraService_method_names[28], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_TrackPoint_(CameraService_method_names[29], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_TrackRectangle_(CameraService_method_names[30], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_TrackStop_(CameraService_method_names[31], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_FocusInStart_(CameraService_method_names[32], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_FocusOutStart_(CameraService_method_names[33], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_FocusStop_(CameraService_method_names[34], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_FocusRange_(CameraService_method_names[35], 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) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_Prepare_, context, request, response); -} - -void CameraService::Stub::async::Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_Prepare_, context, request, response, std::move(f)); -} - -void CameraService::Stub::async::Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_Prepare_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>* CameraService::Stub::PrepareAsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::PrepareResponse, ::mavsdk::rpc::camera::PrepareRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_Prepare_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>* CameraService::Stub::AsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncPrepareRaw(context, request, cq); - result->StartCall(); - return result; -} - ::grpc::Status CameraService::Stub::TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::mavsdk::rpc::camera::TakePhotoResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_TakePhoto_, context, request, response); } @@ -331,6 +314,22 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ListPhotosResponse>* C return result; } +::grpc::ClientReader< ::mavsdk::rpc::camera::CameraListResponse>* CameraService::Stub::SubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::CameraListResponse>::Create(channel_.get(), rpcmethod_SubscribeCameraList_, context, request); +} + +void CameraService::Stub::async::SubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CameraListResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera::CameraListResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeCameraList_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>* CameraService::Stub::AsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::CameraListResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraList_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>* CameraService::Stub::PrepareAsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::CameraListResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraList_, context, request, false, nullptr); +} + ::grpc::ClientReader< ::mavsdk::rpc::camera::ModeResponse>* CameraService::Stub::SubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::ModeResponse>::Create(channel_.get(), rpcmethod_SubscribeMode_, context, request); } @@ -347,20 +346,27 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::ModeResponse>* CameraService:: return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::ModeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeMode_, context, request, false, nullptr); } -::grpc::ClientReader< ::mavsdk::rpc::camera::InformationResponse>* CameraService::Stub::SubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::InformationResponse>::Create(channel_.get(), rpcmethod_SubscribeInformation_, context, request); +::grpc::Status CameraService::Stub::GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::mavsdk::rpc::camera::GetModeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetMode_, context, request, response); } -void CameraService::Stub::async::SubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::InformationResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::camera::InformationResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeInformation_, context, request, reactor); +void CameraService::Stub::async::GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetMode_, context, request, response, std::move(f)); } -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>* CameraService::Stub::AsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::InformationResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeInformation_, context, request, true, tag); +void CameraService::Stub::async::GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetMode_, context, request, response, reactor); } -::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>* CameraService::Stub::PrepareAsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::InformationResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeInformation_, context, request, false, nullptr); +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>* CameraService::Stub::PrepareAsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::GetModeResponse, ::mavsdk::rpc::camera::GetModeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetMode_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>* CameraService::Stub::AsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetModeRaw(context, request, cq); + result->StartCall(); + return result; } ::grpc::ClientReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* CameraService::Stub::SubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request) { @@ -379,6 +385,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* Came return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::VideoStreamInfoResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeVideoStreamInfo_, context, request, false, nullptr); } +::grpc::Status CameraService::Stub::GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetVideoStreamInfo_, context, request, response); +} + +void CameraService::Stub::async::GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetVideoStreamInfo_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetVideoStreamInfo_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* CameraService::Stub::PrepareAsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse, ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetVideoStreamInfo_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* CameraService::Stub::AsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetVideoStreamInfoRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera::CaptureInfoResponse>* CameraService::Stub::SubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::CaptureInfoResponse>::Create(channel_.get(), rpcmethod_SubscribeCaptureInfo_, context, request); } @@ -411,6 +440,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::StatusResponse>* CameraService return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::StatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStatus_, context, request, false, nullptr); } +::grpc::Status CameraService::Stub::GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::mavsdk::rpc::camera::GetStatusResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetStatus_, context, request, response); +} + +void CameraService::Stub::async::GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetStatus_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetStatus_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>* CameraService::Stub::PrepareAsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::GetStatusResponse, ::mavsdk::rpc::camera::GetStatusRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetStatus_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>* CameraService::Stub::AsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetStatusRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>* CameraService::Stub::SubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::CurrentSettingsResponse>::Create(channel_.get(), rpcmethod_SubscribeCurrentSettings_, context, request); } @@ -427,6 +479,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>* Came return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::CurrentSettingsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCurrentSettings_, context, request, false, nullptr); } +::grpc::Status CameraService::Stub::GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetCurrentSettings_, context, request, response); +} + +void CameraService::Stub::async::GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetCurrentSettings_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetCurrentSettings_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* CameraService::Stub::PrepareAsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::GetCurrentSettingsResponse, ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetCurrentSettings_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* CameraService::Stub::AsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetCurrentSettingsRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::ClientReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* CameraService::Stub::SubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>::Create(channel_.get(), rpcmethod_SubscribePossibleSettingOptions_, context, request); } @@ -443,6 +518,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>::Create(channel_.get(), cq, rpcmethod_SubscribePossibleSettingOptions_, context, request, false, nullptr); } +::grpc::Status CameraService::Stub::GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetPossibleSettingOptions_, context, request, response); +} + +void CameraService::Stub::async::GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetPossibleSettingOptions_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetPossibleSettingOptions_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* CameraService::Stub::PrepareAsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetPossibleSettingOptions_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* CameraService::Stub::AsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetPossibleSettingOptionsRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::Status CameraService::Stub::SetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::mavsdk::rpc::camera::SetSettingResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetSetting_, context, request, response); } @@ -512,29 +610,6 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FormatStorageResponse> return result; } -::grpc::Status CameraService::Stub::SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::mavsdk::rpc::camera::SelectCameraResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SelectCamera_, context, request, response); -} - -void CameraService::Stub::async::SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SelectCamera_, context, request, response, std::move(f)); -} - -void CameraService::Stub::async::SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SelectCamera_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>* CameraService::Stub::PrepareAsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::SelectCameraResponse, ::mavsdk::rpc::camera::SelectCameraRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SelectCamera_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>* CameraService::Stub::AsyncSelectCameraRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncSelectCameraRaw(context, request, cq); - result->StartCall(); - 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); } @@ -815,16 +890,6 @@ CameraService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[0], ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](CameraService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera::PrepareRequest* req, - ::mavsdk::rpc::camera::PrepareResponse* resp) { - return service->Prepare(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[1], - ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, ::grpc::ServerContext* ctx, @@ -833,7 +898,7 @@ CameraService::Service::Service() { return service->TakePhoto(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[2], + CameraService_method_names[1], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StartPhotoIntervalRequest, ::mavsdk::rpc::camera::StartPhotoIntervalResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -843,7 +908,7 @@ CameraService::Service::Service() { return service->StartPhotoInterval(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[3], + CameraService_method_names[2], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StopPhotoIntervalRequest, ::mavsdk::rpc::camera::StopPhotoIntervalResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -853,7 +918,7 @@ CameraService::Service::Service() { return service->StopPhotoInterval(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[4], + CameraService_method_names[3], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StartVideoRequest, ::mavsdk::rpc::camera::StartVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -863,7 +928,7 @@ CameraService::Service::Service() { return service->StartVideo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[5], + CameraService_method_names[4], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StopVideoRequest, ::mavsdk::rpc::camera::StopVideoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -873,7 +938,7 @@ CameraService::Service::Service() { return service->StopVideo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[6], + CameraService_method_names[5], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StartVideoStreamingRequest, ::mavsdk::rpc::camera::StartVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -883,7 +948,7 @@ CameraService::Service::Service() { return service->StartVideoStreaming(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[7], + CameraService_method_names[6], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::StopVideoStreamingRequest, ::mavsdk::rpc::camera::StopVideoStreamingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -893,7 +958,7 @@ CameraService::Service::Service() { return service->StopVideoStreaming(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[8], + CameraService_method_names[7], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::SetModeRequest, ::mavsdk::rpc::camera::SetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -903,7 +968,7 @@ CameraService::Service::Service() { return service->SetMode(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[9], + CameraService_method_names[8], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ListPhotosRequest, ::mavsdk::rpc::camera::ListPhotosResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -912,6 +977,16 @@ CameraService::Service::Service() { ::mavsdk::rpc::camera::ListPhotosResponse* resp) { return service->ListPhotos(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[9], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribeCameraListRequest, ::mavsdk::rpc::camera::CameraListResponse>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::SubscribeCameraListRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::camera::CameraListResponse>* writer) { + return service->SubscribeCameraList(ctx, req, writer); + }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, @@ -924,13 +999,13 @@ CameraService::Service::Service() { }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[11], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribeInformationRequest, ::mavsdk::rpc::camera::InformationResponse>( + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera::SubscribeInformationRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::camera::InformationResponse>* writer) { - return service->SubscribeInformation(ctx, req, writer); + const ::mavsdk::rpc::camera::GetModeRequest* req, + ::mavsdk::rpc::camera::GetModeResponse* resp) { + return service->GetMode(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[12], @@ -944,6 +1019,16 @@ CameraService::Service::Service() { }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[13], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* req, + ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* resp) { + return service->GetVideoStreamInfo(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest, ::mavsdk::rpc::camera::CaptureInfoResponse>( [](CameraService::Service* service, @@ -953,7 +1038,7 @@ CameraService::Service::Service() { return service->SubscribeCaptureInfo(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[14], + CameraService_method_names[15], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribeStatusRequest, ::mavsdk::rpc::camera::StatusResponse>( [](CameraService::Service* service, @@ -963,7 +1048,17 @@ CameraService::Service::Service() { return service->SubscribeStatus(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[15], + CameraService_method_names[16], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::GetStatusRequest* req, + ::mavsdk::rpc::camera::GetStatusResponse* resp) { + return service->GetStatus(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[17], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest, ::mavsdk::rpc::camera::CurrentSettingsResponse>( [](CameraService::Service* service, @@ -973,7 +1068,17 @@ CameraService::Service::Service() { return service->SubscribeCurrentSettings(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[16], + CameraService_method_names[18], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* req, + ::mavsdk::rpc::camera::GetCurrentSettingsResponse* resp) { + return service->GetCurrentSettings(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[19], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< CameraService::Service, ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest, ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>( [](CameraService::Service* service, @@ -983,7 +1088,17 @@ CameraService::Service::Service() { return service->SubscribePossibleSettingOptions(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[17], + CameraService_method_names[20], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](CameraService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* req, + ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* resp) { + return service->GetPossibleSettingOptions(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::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -993,7 +1108,7 @@ CameraService::Service::Service() { return service->SetSetting(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[18], + CameraService_method_names[22], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::GetSettingRequest, ::mavsdk::rpc::camera::GetSettingResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1003,7 +1118,7 @@ CameraService::Service::Service() { return service->GetSetting(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[19], + CameraService_method_names[23], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::FormatStorageRequest, ::mavsdk::rpc::camera::FormatStorageResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1013,17 +1128,7 @@ CameraService::Service::Service() { return service->FormatStorage(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[20], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](CameraService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::camera::SelectCameraRequest* req, - ::mavsdk::rpc::camera::SelectCameraResponse* resp) { - return service->SelectCamera(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[21], + CameraService_method_names[24], ::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, @@ -1033,7 +1138,7 @@ CameraService::Service::Service() { return service->ResetSettings(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[22], + CameraService_method_names[25], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1043,7 +1148,7 @@ CameraService::Service::Service() { return service->ZoomInStart(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[23], + CameraService_method_names[26], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1053,7 +1158,7 @@ CameraService::Service::Service() { return service->ZoomOutStart(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[24], + CameraService_method_names[27], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1063,7 +1168,7 @@ CameraService::Service::Service() { return service->ZoomStop(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[25], + CameraService_method_names[28], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1073,7 +1178,7 @@ CameraService::Service::Service() { return service->ZoomRange(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[26], + CameraService_method_names[29], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1083,7 +1188,7 @@ CameraService::Service::Service() { return service->TrackPoint(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[27], + CameraService_method_names[30], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1093,7 +1198,7 @@ CameraService::Service::Service() { return service->TrackRectangle(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[28], + CameraService_method_names[31], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1103,7 +1208,7 @@ CameraService::Service::Service() { return service->TrackStop(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[29], + CameraService_method_names[32], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1113,7 +1218,7 @@ CameraService::Service::Service() { return service->FocusInStart(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[30], + CameraService_method_names[33], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1123,7 +1228,7 @@ CameraService::Service::Service() { return service->FocusOutStart(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[31], + CameraService_method_names[34], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1133,7 +1238,7 @@ CameraService::Service::Service() { return service->FocusStop(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - CameraService_method_names[32], + CameraService_method_names[35], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< CameraService::Service, ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](CameraService::Service* service, @@ -1147,13 +1252,6 @@ CameraService::Service::Service() { CameraService::Service::~Service() { } -::grpc::Status CameraService::Service::Prepare(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - ::grpc::Status CameraService::Service::TakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response) { (void) context; (void) request; @@ -1217,20 +1315,27 @@ ::grpc::Status CameraService::Service::ListPhotos(::grpc::ServerContext* context return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::SubscribeMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::ModeResponse>* writer) { +::grpc::Status CameraService::Service::SubscribeCameraList(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* writer) { (void) context; (void) request; (void) writer; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::SubscribeInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* writer) { +::grpc::Status CameraService::Service::SubscribeMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::ModeResponse>* writer) { (void) context; (void) request; (void) writer; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::GetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraService::Service::SubscribeVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* writer) { (void) context; (void) request; @@ -1238,6 +1343,13 @@ ::grpc::Status CameraService::Service::SubscribeVideoStreamInfo(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::GetVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraService::Service::SubscribeCaptureInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CaptureInfoResponse>* writer) { (void) context; (void) request; @@ -1252,6 +1364,13 @@ ::grpc::Status CameraService::Service::SubscribeStatus(::grpc::ServerContext* co return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::GetStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraService::Service::SubscribeCurrentSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CurrentSettingsResponse>* writer) { (void) context; (void) request; @@ -1259,6 +1378,13 @@ ::grpc::Status CameraService::Service::SubscribeCurrentSettings(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::GetCurrentSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status CameraService::Service::SubscribePossibleSettingOptions(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* writer) { (void) context; (void) request; @@ -1266,28 +1392,28 @@ ::grpc::Status CameraService::Service::SubscribePossibleSettingOptions(::grpc::S return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::SetSetting(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SetSettingRequest* request, ::mavsdk::rpc::camera::SetSettingResponse* response) { +::grpc::Status CameraService::Service::GetPossibleSettingOptions(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response) { (void) context; (void) request; (void) response; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::GetSetting(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetSettingRequest* request, ::mavsdk::rpc::camera::GetSettingResponse* response) { +::grpc::Status CameraService::Service::SetSetting(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SetSettingRequest* request, ::mavsdk::rpc::camera::SetSettingResponse* response) { (void) context; (void) request; (void) response; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::FormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response) { +::grpc::Status CameraService::Service::GetSetting(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetSettingRequest* request, ::mavsdk::rpc::camera::GetSettingResponse* response) { (void) context; (void) request; (void) response; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status CameraService::Service::SelectCamera(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response) { +::grpc::Status CameraService::Service::FormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response) { (void) context; (void) request; (void) response; 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 49a02a550e..ea8d3ffde5 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h @@ -46,15 +46,6 @@ class CameraService final { public: virtual ~StubInterface() {} // - // Prepare the camera plugin (e.g. download the camera definition, etc). - virtual ::grpc::Status Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::mavsdk::rpc::camera::PrepareResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>> AsyncPrepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>>(AsyncPrepareRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>> PrepareAsyncPrepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>>(PrepareAsyncPrepareRaw(context, request, cq)); - } - // // Take one photo. virtual ::grpc::Status TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::mavsdk::rpc::camera::TakePhotoResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TakePhotoResponse>> AsyncTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) { @@ -136,6 +127,20 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ListPhotosResponse>>(PrepareAsyncListPhotosRaw(context, request, cq)); } // + // Subscribe to list of cameras. + // + // This allows to find out what cameras are connected to the system. + // Based on the camera ID, we can then address a specific camera. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>> SubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>>(SubscribeCameraListRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>> AsyncSubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>>(AsyncSubscribeCameraListRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>> PrepareAsyncSubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>>(PrepareAsyncSubscribeCameraListRaw(context, request, cq)); + } + // // Subscribe to camera mode updates. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::ModeResponse>> SubscribeMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::ModeResponse>>(SubscribeModeRaw(context, request)); @@ -147,15 +152,13 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::ModeResponse>>(PrepareAsyncSubscribeModeRaw(context, request, cq)); } // - // Subscribe to camera information updates. - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::InformationResponse>> SubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::InformationResponse>>(SubscribeInformationRaw(context, request)); + // Get camera mode. + virtual ::grpc::Status GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::mavsdk::rpc::camera::GetModeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>> AsyncGetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>>(AsyncGetModeRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>> AsyncSubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>>(AsyncSubscribeInformationRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>> PrepareAsyncSubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>>(PrepareAsyncSubscribeInformationRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>> PrepareAsyncGetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>>(PrepareAsyncGetModeRaw(context, request, cq)); } // // Subscribe to video stream info updates. @@ -169,6 +172,15 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::VideoStreamInfoResponse>>(PrepareAsyncSubscribeVideoStreamInfoRaw(context, request, cq)); } // + // Get video stream info. + virtual ::grpc::Status GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>> AsyncGetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>>(AsyncGetVideoStreamInfoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>> PrepareAsyncGetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>>(PrepareAsyncGetVideoStreamInfoRaw(context, request, cq)); + } + // // Subscribe to capture info updates. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CaptureInfoResponse>> SubscribeCaptureInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CaptureInfoResponse>>(SubscribeCaptureInfoRaw(context, request)); @@ -191,6 +203,15 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::StatusResponse>>(PrepareAsyncSubscribeStatusRaw(context, request, cq)); } // + // Get camera status. + virtual ::grpc::Status GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::mavsdk::rpc::camera::GetStatusResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>> AsyncGetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>>(AsyncGetStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>> PrepareAsyncGetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>>(PrepareAsyncGetStatusRaw(context, request, cq)); + } + // // Get the list of current camera settings. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>> SubscribeCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>>(SubscribeCurrentSettingsRaw(context, request)); @@ -202,6 +223,15 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>>(PrepareAsyncSubscribeCurrentSettingsRaw(context, request, cq)); } // + // Get current settings. + virtual ::grpc::Status GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>> AsyncGetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>>(AsyncGetCurrentSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>> PrepareAsyncGetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>>(PrepareAsyncGetCurrentSettingsRaw(context, request, cq)); + } + // // Get the list of settings that can be changed. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>> SubscribePossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>>(SubscribePossibleSettingOptionsRaw(context, request)); @@ -213,6 +243,15 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>>(PrepareAsyncSubscribePossibleSettingOptionsRaw(context, request, cq)); } // + // Get possible setting options. + virtual ::grpc::Status GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>> AsyncGetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>>(AsyncGetPossibleSettingOptionsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>> PrepareAsyncGetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>>(PrepareAsyncGetPossibleSettingOptionsRaw(context, request, cq)); + } + // // Set a setting to some value. // // Only setting_id of setting and option_id of option needs to be set. @@ -246,17 +285,6 @@ class CameraService final { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FormatStorageResponse>>(PrepareAsyncFormatStorageRaw(context, request, cq)); } // - // Select current camera . - // - // Bind the plugin instance to a specific camera_id - virtual ::grpc::Status SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::mavsdk::rpc::camera::SelectCameraResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>> AsyncSelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SelectCameraResponse>>(AsyncSelectCameraRaw(context, request, cq)); - } - 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 @@ -370,10 +398,6 @@ class CameraService final { public: virtual ~async_interface() {} // - // Prepare the camera plugin (e.g. download the camera definition, etc). - virtual void Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, std::function) = 0; - virtual void Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // // Take one photo. virtual void TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response, std::function) = 0; virtual void TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -410,27 +434,50 @@ class CameraService final { virtual void ListPhotos(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response, std::function) = 0; virtual void ListPhotos(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // + // Subscribe to list of cameras. + // + // This allows to find out what cameras are connected to the system. + // Based on the camera ID, we can then address a specific camera. + virtual void SubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CameraListResponse>* reactor) = 0; + // // Subscribe to camera mode updates. virtual void SubscribeMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::ModeResponse>* reactor) = 0; // - // Subscribe to camera information updates. - virtual void SubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::InformationResponse>* reactor) = 0; + // Get camera mode. + virtual void GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, std::function) = 0; + virtual void GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // // Subscribe to video stream info updates. virtual void SubscribeVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* reactor) = 0; // + // Get video stream info. + virtual void GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, std::function) = 0; + virtual void GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // // Subscribe to capture info updates. virtual void SubscribeCaptureInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CaptureInfoResponse>* reactor) = 0; // // Subscribe to camera status updates. virtual void SubscribeStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::StatusResponse>* reactor) = 0; // + // Get camera status. + virtual void GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, std::function) = 0; + virtual void GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // // Get the list of current camera settings. virtual void SubscribeCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CurrentSettingsResponse>* reactor) = 0; // + // Get current settings. + virtual void GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, std::function) = 0; + virtual void GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // // Get the list of settings that can be changed. virtual void SubscribePossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* reactor) = 0; // + // Get possible setting options. + virtual void GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, std::function) = 0; + virtual void GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // // Set a setting to some value. // // Only setting_id of setting and option_id of option needs to be set. @@ -449,12 +496,6 @@ class CameraService final { virtual void FormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response, std::function) = 0; virtual void FormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // - // Select current camera . - // - // 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 @@ -509,8 +550,6 @@ class CameraService final { virtual class async_interface* async() { return nullptr; } class async_interface* experimental_async() { return async(); } private: - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>* AsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::PrepareResponse>* PrepareAsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TakePhotoResponse>* AsyncTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TakePhotoResponse>* PrepareAsyncTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::StartPhotoIntervalResponse>* AsyncStartPhotoIntervalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -529,35 +568,43 @@ class CameraService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SetModeResponse>* PrepareAsyncSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ListPhotosResponse>* AsyncListPhotosRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ListPhotosResponse>* PrepareAsyncListPhotosRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>* SubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>* AsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CameraListResponse>* PrepareAsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::ModeResponse>* SubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::ModeResponse>* AsyncSubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::ModeResponse>* PrepareAsyncSubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::InformationResponse>* SubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>* AsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::InformationResponse>* PrepareAsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>* AsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetModeResponse>* PrepareAsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* SubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* AsyncSubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* PrepareAsyncSubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* AsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* PrepareAsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CaptureInfoResponse>* SubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CaptureInfoResponse>* AsyncSubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CaptureInfoResponse>* PrepareAsyncSubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::StatusResponse>* SubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::StatusResponse>* AsyncSubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::StatusResponse>* PrepareAsyncSubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>* AsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetStatusResponse>* PrepareAsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>* SubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>* AsyncSubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::CurrentSettingsResponse>* PrepareAsyncSubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* AsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* PrepareAsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* SubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* AsyncSubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* PrepareAsyncSubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* AsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* PrepareAsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SetSettingResponse>* AsyncSetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::SetSettingResponse>* PrepareAsyncSetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetSettingResponse>* AsyncGetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::GetSettingResponse>* PrepareAsyncGetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FormatStorageResponse>* AsyncFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest& request, ::grpc::CompletionQueue* cq) = 0; 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; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>* AsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -586,13 +633,6 @@ class CameraService final { class Stub final : public StubInterface { public: Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); - ::grpc::Status Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::mavsdk::rpc::camera::PrepareResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>> AsyncPrepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>>(AsyncPrepareRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>> PrepareAsyncPrepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>>(PrepareAsyncPrepareRaw(context, request, cq)); - } ::grpc::Status TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::mavsdk::rpc::camera::TakePhotoResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TakePhotoResponse>> AsyncTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TakePhotoResponse>>(AsyncTakePhotoRaw(context, request, cq)); @@ -656,6 +696,15 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ListPhotosResponse>> PrepareAsyncListPhotos(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ListPhotosResponse>>(PrepareAsyncListPhotosRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CameraListResponse>> SubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CameraListResponse>>(SubscribeCameraListRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>> AsyncSubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>>(AsyncSubscribeCameraListRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>> PrepareAsyncSubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>>(PrepareAsyncSubscribeCameraListRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::ModeResponse>> SubscribeMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::ModeResponse>>(SubscribeModeRaw(context, request)); } @@ -665,14 +714,12 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::ModeResponse>> PrepareAsyncSubscribeMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::ModeResponse>>(PrepareAsyncSubscribeModeRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::InformationResponse>> SubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::InformationResponse>>(SubscribeInformationRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>> AsyncSubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>>(AsyncSubscribeInformationRaw(context, request, cq, tag)); + ::grpc::Status GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::mavsdk::rpc::camera::GetModeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>> AsyncGetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>>(AsyncGetModeRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>> PrepareAsyncSubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>>(PrepareAsyncSubscribeInformationRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>> PrepareAsyncGetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>>(PrepareAsyncGetModeRaw(context, request, cq)); } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>> SubscribeVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>>(SubscribeVideoStreamInfoRaw(context, request)); @@ -683,6 +730,13 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>> PrepareAsyncSubscribeVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>>(PrepareAsyncSubscribeVideoStreamInfoRaw(context, request, cq)); } + ::grpc::Status GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>> AsyncGetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>>(AsyncGetVideoStreamInfoRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>> PrepareAsyncGetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>>(PrepareAsyncGetVideoStreamInfoRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CaptureInfoResponse>> SubscribeCaptureInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CaptureInfoResponse>>(SubscribeCaptureInfoRaw(context, request)); } @@ -701,6 +755,13 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::StatusResponse>> PrepareAsyncSubscribeStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::StatusResponse>>(PrepareAsyncSubscribeStatusRaw(context, request, cq)); } + ::grpc::Status GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::mavsdk::rpc::camera::GetStatusResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>> AsyncGetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>>(AsyncGetStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>> PrepareAsyncGetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>>(PrepareAsyncGetStatusRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>> SubscribeCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>>(SubscribeCurrentSettingsRaw(context, request)); } @@ -710,6 +771,13 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>> PrepareAsyncSubscribeCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>>(PrepareAsyncSubscribeCurrentSettingsRaw(context, request, cq)); } + ::grpc::Status GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>> AsyncGetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>>(AsyncGetCurrentSettingsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>> PrepareAsyncGetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>>(PrepareAsyncGetCurrentSettingsRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>> SubscribePossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>>(SubscribePossibleSettingOptionsRaw(context, request)); } @@ -719,6 +787,13 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>> PrepareAsyncSubscribePossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>>(PrepareAsyncSubscribePossibleSettingOptionsRaw(context, request, cq)); } + ::grpc::Status GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>> AsyncGetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>>(AsyncGetPossibleSettingOptionsRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>> PrepareAsyncGetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>>(PrepareAsyncGetPossibleSettingOptionsRaw(context, request, cq)); + } ::grpc::Status SetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::mavsdk::rpc::camera::SetSettingResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SetSettingResponse>> AsyncSetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SetSettingResponse>>(AsyncSetSettingRaw(context, request, cq)); @@ -740,13 +815,6 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FormatStorageResponse>> PrepareAsyncFormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FormatStorageResponse>>(PrepareAsyncFormatStorageRaw(context, request, cq)); } - ::grpc::Status SelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::mavsdk::rpc::camera::SelectCameraResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>> AsyncSelectCamera(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SelectCameraResponse>>(AsyncSelectCameraRaw(context, request, cq)); - } - 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)); @@ -834,8 +902,6 @@ class CameraService final { class async final : public StubInterface::async_interface { public: - void Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, std::function) override; - void Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response, std::function) override; void TakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void StartPhotoInterval(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* request, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* response, std::function) override; @@ -854,21 +920,29 @@ class CameraService final { void SetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetModeRequest* request, ::mavsdk::rpc::camera::SetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void ListPhotos(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response, std::function) override; void ListPhotos(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SubscribeCameraList(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CameraListResponse>* reactor) override; void SubscribeMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::ModeResponse>* reactor) override; - void SubscribeInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::InformationResponse>* reactor) override; + void GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, std::function) override; + void GetMode(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* reactor) override; + void GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, std::function) override; + void GetVideoStreamInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeCaptureInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CaptureInfoResponse>* reactor) override; void SubscribeStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::StatusResponse>* reactor) override; + void GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, std::function) override; + void GetStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::CurrentSettingsResponse>* reactor) override; + void GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, std::function) override; + void GetCurrentSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribePossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* reactor) override; + void GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, std::function) override; + void GetPossibleSettingOptions(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest* request, ::mavsdk::rpc::camera::SetSettingResponse* response, std::function) override; void SetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest* request, ::mavsdk::rpc::camera::SetSettingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void GetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest* request, ::mavsdk::rpc::camera::GetSettingResponse* response, std::function) override; void GetSetting(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest* request, ::mavsdk::rpc::camera::GetSettingResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void FormatStorage(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response, std::function) override; 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; void ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, std::function) override; @@ -904,8 +978,6 @@ class CameraService final { private: std::shared_ptr< ::grpc::ChannelInterface> channel_; class async async_stub_{this}; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>* AsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::PrepareResponse>* PrepareAsyncPrepareRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TakePhotoResponse>* AsyncTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TakePhotoResponse>* PrepareAsyncTakePhotoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::StartPhotoIntervalResponse>* AsyncStartPhotoIntervalRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest& request, ::grpc::CompletionQueue* cq) override; @@ -924,35 +996,43 @@ class CameraService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SetModeResponse>* PrepareAsyncSetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetModeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ListPhotosResponse>* AsyncListPhotosRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ListPhotosResponse>* PrepareAsyncListPhotosRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::camera::CameraListResponse>* SubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>* AsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CameraListResponse>* PrepareAsyncSubscribeCameraListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::ModeResponse>* SubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::ModeResponse>* AsyncSubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::ModeResponse>* PrepareAsyncSubscribeModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::camera::InformationResponse>* SubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>* AsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::InformationResponse>* PrepareAsyncSubscribeInformationRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>* AsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetModeResponse>* PrepareAsyncGetModeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetModeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* SubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* AsyncSubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* PrepareAsyncSubscribeVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* AsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* PrepareAsyncGetVideoStreamInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::CaptureInfoResponse>* SubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CaptureInfoResponse>* AsyncSubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CaptureInfoResponse>* PrepareAsyncSubscribeCaptureInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::StatusResponse>* SubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::StatusResponse>* AsyncSubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::StatusResponse>* PrepareAsyncSubscribeStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>* AsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetStatusResponse>* PrepareAsyncGetStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetStatusRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>* SubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>* AsyncSubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::CurrentSettingsResponse>* PrepareAsyncSubscribeCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* AsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* PrepareAsyncGetCurrentSettingsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* SubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* AsyncSubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* PrepareAsyncSubscribePossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* AsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* PrepareAsyncGetPossibleSettingOptionsRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SetSettingResponse>* AsyncSetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::SetSettingResponse>* PrepareAsyncSetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::SetSettingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetSettingResponse>* AsyncGetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::GetSettingResponse>* PrepareAsyncGetSettingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::GetSettingRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FormatStorageResponse>* AsyncFormatStorageRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest& request, ::grpc::CompletionQueue* cq) override; ::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; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>* AsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) override; @@ -977,7 +1057,6 @@ class CameraService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>* PrepareAsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>* AsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>* PrepareAsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) override; - const ::grpc::internal::RpcMethod rpcmethod_Prepare_; const ::grpc::internal::RpcMethod rpcmethod_TakePhoto_; const ::grpc::internal::RpcMethod rpcmethod_StartPhotoInterval_; const ::grpc::internal::RpcMethod rpcmethod_StopPhotoInterval_; @@ -987,17 +1066,21 @@ class CameraService final { const ::grpc::internal::RpcMethod rpcmethod_StopVideoStreaming_; const ::grpc::internal::RpcMethod rpcmethod_SetMode_; const ::grpc::internal::RpcMethod rpcmethod_ListPhotos_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeCameraList_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeMode_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeInformation_; + const ::grpc::internal::RpcMethod rpcmethod_GetMode_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeVideoStreamInfo_; + const ::grpc::internal::RpcMethod rpcmethod_GetVideoStreamInfo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCaptureInfo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStatus_; + const ::grpc::internal::RpcMethod rpcmethod_GetStatus_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCurrentSettings_; + const ::grpc::internal::RpcMethod rpcmethod_GetCurrentSettings_; const ::grpc::internal::RpcMethod rpcmethod_SubscribePossibleSettingOptions_; + const ::grpc::internal::RpcMethod rpcmethod_GetPossibleSettingOptions_; const ::grpc::internal::RpcMethod rpcmethod_SetSetting_; const ::grpc::internal::RpcMethod rpcmethod_GetSetting_; const ::grpc::internal::RpcMethod rpcmethod_FormatStorage_; - const ::grpc::internal::RpcMethod rpcmethod_SelectCamera_; const ::grpc::internal::RpcMethod rpcmethod_ResetSettings_; const ::grpc::internal::RpcMethod rpcmethod_ZoomInStart_; const ::grpc::internal::RpcMethod rpcmethod_ZoomOutStart_; @@ -1018,9 +1101,6 @@ class CameraService final { Service(); virtual ~Service(); // - // Prepare the camera plugin (e.g. download the camera definition, etc). - virtual ::grpc::Status Prepare(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response); - // // Take one photo. virtual ::grpc::Status TakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response); // @@ -1048,27 +1128,45 @@ class CameraService final { // List photos available on the camera. virtual ::grpc::Status ListPhotos(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response); // + // Subscribe to list of cameras. + // + // This allows to find out what cameras are connected to the system. + // Based on the camera ID, we can then address a specific camera. + virtual ::grpc::Status SubscribeCameraList(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* writer); + // // Subscribe to camera mode updates. virtual ::grpc::Status SubscribeMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeModeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::ModeResponse>* writer); // - // Subscribe to camera information updates. - virtual ::grpc::Status SubscribeInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* writer); + // Get camera mode. + virtual ::grpc::Status GetMode(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response); // // Subscribe to video stream info updates. virtual ::grpc::Status SubscribeVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::VideoStreamInfoResponse>* writer); // + // Get video stream info. + virtual ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response); + // // Subscribe to capture info updates. virtual ::grpc::Status SubscribeCaptureInfo(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CaptureInfoResponse>* writer); // // Subscribe to camera status updates. virtual ::grpc::Status SubscribeStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::StatusResponse>* writer); // + // Get camera status. + virtual ::grpc::Status GetStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response); + // // Get the list of current camera settings. virtual ::grpc::Status SubscribeCurrentSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CurrentSettingsResponse>* writer); // + // Get current settings. + virtual ::grpc::Status GetCurrentSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response); + // // Get the list of settings that can be changed. virtual ::grpc::Status SubscribePossibleSettingOptions(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* writer); // + // Get possible setting options. + virtual ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response); + // // Set a setting to some value. // // Only setting_id of setting and option_id of option needs to be set. @@ -1084,11 +1182,6 @@ class CameraService final { // This will delete all content of the camera storage! virtual ::grpc::Status FormatStorage(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response); // - // Select current camera . - // - // 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 @@ -1128,32 +1221,12 @@ class CameraService final { virtual ::grpc::Status FocusRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response); }; template - class WithAsyncMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_Prepare() { - ::grpc::Service::MarkMethodAsync(0); - } - ~WithAsyncMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestPrepare(::grpc::ServerContext* context, ::mavsdk::rpc::camera::PrepareRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::PrepareResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template class WithAsyncMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_TakePhoto() { - ::grpc::Service::MarkMethodAsync(1); + ::grpc::Service::MarkMethodAsync(0); } ~WithAsyncMethod_TakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -1164,7 +1237,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTakePhoto(::grpc::ServerContext* context, ::mavsdk::rpc::camera::TakePhotoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::TakePhotoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1173,7 +1246,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodAsync(2); + ::grpc::Service::MarkMethodAsync(1); } ~WithAsyncMethod_StartPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -1184,7 +1257,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartPhotoInterval(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StartPhotoIntervalRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StartPhotoIntervalResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1193,7 +1266,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodAsync(3); + ::grpc::Service::MarkMethodAsync(2); } ~WithAsyncMethod_StopPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -1204,7 +1277,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopPhotoInterval(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StopPhotoIntervalRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StopPhotoIntervalResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1213,7 +1286,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StartVideo() { - ::grpc::Service::MarkMethodAsync(4); + ::grpc::Service::MarkMethodAsync(3); } ~WithAsyncMethod_StartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1224,7 +1297,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StartVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StartVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1233,7 +1306,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StopVideo() { - ::grpc::Service::MarkMethodAsync(5); + ::grpc::Service::MarkMethodAsync(4); } ~WithAsyncMethod_StopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -1244,7 +1317,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopVideo(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StopVideoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StopVideoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1253,7 +1326,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(5); } ~WithAsyncMethod_StartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1264,7 +1337,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StartVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StartVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1273,7 +1346,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(6); } ~WithAsyncMethod_StopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -1284,7 +1357,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopVideoStreaming(::grpc::ServerContext* context, ::mavsdk::rpc::camera::StopVideoStreamingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::StopVideoStreamingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1293,7 +1366,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetMode() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(7); } ~WithAsyncMethod_SetMode() override { BaseClassMustBeDerivedFromService(this); @@ -1304,7 +1377,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SetModeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::SetModeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1313,7 +1386,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ListPhotos() { - ::grpc::Service::MarkMethodAsync(9); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_ListPhotos() override { BaseClassMustBeDerivedFromService(this); @@ -1324,7 +1397,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestListPhotos(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ListPhotosRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ListPhotosResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeCameraList : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodAsync(9); + } + ~WithAsyncMethod_SubscribeCameraList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeCameraList(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribeCameraListRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::CameraListResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1348,23 +1441,23 @@ class CameraService final { } }; template - class WithAsyncMethod_SubscribeInformation : public BaseClass { + class WithAsyncMethod_GetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithAsyncMethod_SubscribeInformation() { + WithAsyncMethod_GetMode() { ::grpc::Service::MarkMethodAsync(11); } - ~WithAsyncMethod_SubscribeInformation() override { + ~WithAsyncMethod_GetMode() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSubscribeInformation(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribeInformationRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::InformationResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + void RequestGetMode(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetModeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetModeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1388,12 +1481,32 @@ class CameraService final { } }; template + class WithAsyncMethod_GetVideoStreamInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetVideoStreamInfo() { + ::grpc::Service::MarkMethodAsync(13); + } + ~WithAsyncMethod_GetVideoStreamInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetVideoStreamInfo(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(13, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_SubscribeCaptureInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeCaptureInfo() { - ::grpc::Service::MarkMethodAsync(13); + ::grpc::Service::MarkMethodAsync(14); } ~WithAsyncMethod_SubscribeCaptureInfo() override { BaseClassMustBeDerivedFromService(this); @@ -1404,7 +1517,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureInfo(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::CaptureInfoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1413,7 +1526,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodAsync(14); + ::grpc::Service::MarkMethodAsync(15); } ~WithAsyncMethod_SubscribeStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1424,7 +1537,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribeStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::StatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetStatus() { + ::grpc::Service::MarkMethodAsync(16); + } + ~WithAsyncMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetStatus(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(16, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1433,7 +1566,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodAsync(15); + ::grpc::Service::MarkMethodAsync(17); } ~WithAsyncMethod_SubscribeCurrentSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1444,7 +1577,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCurrentSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::CurrentSettingsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodAsync(18); + } + ~WithAsyncMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetCurrentSettings(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(18, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1453,7 +1606,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodAsync(16); + ::grpc::Service::MarkMethodAsync(19); } ~WithAsyncMethod_SubscribePossibleSettingOptions() override { BaseClassMustBeDerivedFromService(this); @@ -1464,7 +1617,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribePossibleSettingOptions(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_GetPossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodAsync(20); + } + ~WithAsyncMethod_GetPossibleSettingOptions() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetPossibleSettingOptions(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1473,7 +1646,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetSetting() { - ::grpc::Service::MarkMethodAsync(17); + ::grpc::Service::MarkMethodAsync(21); } ~WithAsyncMethod_SetSetting() override { BaseClassMustBeDerivedFromService(this); @@ -1484,7 +1657,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetSetting(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SetSettingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::SetSettingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(17, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1493,7 +1666,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_GetSetting() { - ::grpc::Service::MarkMethodAsync(18); + ::grpc::Service::MarkMethodAsync(22); } ~WithAsyncMethod_GetSetting() override { BaseClassMustBeDerivedFromService(this); @@ -1504,7 +1677,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestGetSetting(::grpc::ServerContext* context, ::mavsdk::rpc::camera::GetSettingRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::GetSettingResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(18, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1513,7 +1686,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_FormatStorage() { - ::grpc::Service::MarkMethodAsync(19); + ::grpc::Service::MarkMethodAsync(23); } ~WithAsyncMethod_FormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -1524,27 +1697,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFormatStorage(::grpc::ServerContext* context, ::mavsdk::rpc::camera::FormatStorageRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::FormatStorageResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(19, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SelectCamera : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SelectCamera() { - ::grpc::Service::MarkMethodAsync(20); - } - ~WithAsyncMethod_SelectCamera() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSelectCamera(::grpc::ServerContext* context, ::mavsdk::rpc::camera::SelectCameraRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::SelectCameraResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(20, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(23, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1553,7 +1706,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ResetSettings() { - ::grpc::Service::MarkMethodAsync(21); + ::grpc::Service::MarkMethodAsync(24); } ~WithAsyncMethod_ResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -1564,7 +1717,7 @@ class CameraService final { 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); + ::grpc::Service::RequestAsyncUnary(24, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1573,7 +1726,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ZoomInStart() { - ::grpc::Service::MarkMethodAsync(22); + ::grpc::Service::MarkMethodAsync(25); } ~WithAsyncMethod_ZoomInStart() override { BaseClassMustBeDerivedFromService(this); @@ -1584,7 +1737,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomInStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ZoomInStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(25, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1593,7 +1746,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodAsync(23); + ::grpc::Service::MarkMethodAsync(26); } ~WithAsyncMethod_ZoomOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -1604,7 +1757,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomOutStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ZoomOutStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(23, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(26, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1613,7 +1766,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ZoomStop() { - ::grpc::Service::MarkMethodAsync(24); + ::grpc::Service::MarkMethodAsync(27); } ~WithAsyncMethod_ZoomStop() override { BaseClassMustBeDerivedFromService(this); @@ -1624,7 +1777,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomStop(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ZoomStopRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ZoomStopResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(24, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(27, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1633,7 +1786,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ZoomRange() { - ::grpc::Service::MarkMethodAsync(25); + ::grpc::Service::MarkMethodAsync(28); } ~WithAsyncMethod_ZoomRange() override { BaseClassMustBeDerivedFromService(this); @@ -1644,7 +1797,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomRange(::grpc::ServerContext* context, ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::ZoomRangeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(25, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(28, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1653,7 +1806,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_TrackPoint() { - ::grpc::Service::MarkMethodAsync(26); + ::grpc::Service::MarkMethodAsync(29); } ~WithAsyncMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); @@ -1664,7 +1817,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackPoint(::grpc::ServerContext* context, ::mavsdk::rpc::camera::TrackPointRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::TrackPointResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(26, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(29, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1673,7 +1826,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_TrackRectangle() { - ::grpc::Service::MarkMethodAsync(27); + ::grpc::Service::MarkMethodAsync(30); } ~WithAsyncMethod_TrackRectangle() override { BaseClassMustBeDerivedFromService(this); @@ -1684,7 +1837,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackRectangle(::grpc::ServerContext* context, ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::TrackRectangleResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(27, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(30, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1693,7 +1846,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_TrackStop() { - ::grpc::Service::MarkMethodAsync(28); + ::grpc::Service::MarkMethodAsync(31); } ~WithAsyncMethod_TrackStop() override { BaseClassMustBeDerivedFromService(this); @@ -1704,7 +1857,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackStop(::grpc::ServerContext* context, ::mavsdk::rpc::camera::TrackStopRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::TrackStopResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(28, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(31, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1713,7 +1866,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_FocusInStart() { - ::grpc::Service::MarkMethodAsync(29); + ::grpc::Service::MarkMethodAsync(32); } ~WithAsyncMethod_FocusInStart() override { BaseClassMustBeDerivedFromService(this); @@ -1724,7 +1877,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusInStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera::FocusInStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::FocusInStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(29, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(32, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1733,7 +1886,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_FocusOutStart() { - ::grpc::Service::MarkMethodAsync(30); + ::grpc::Service::MarkMethodAsync(33); } ~WithAsyncMethod_FocusOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -1744,7 +1897,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusOutStart(::grpc::ServerContext* context, ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::FocusOutStartResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(30, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(33, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1753,7 +1906,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_FocusStop() { - ::grpc::Service::MarkMethodAsync(31); + ::grpc::Service::MarkMethodAsync(34); } ~WithAsyncMethod_FocusStop() override { BaseClassMustBeDerivedFromService(this); @@ -1764,7 +1917,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusStop(::grpc::ServerContext* context, ::mavsdk::rpc::camera::FocusStopRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::FocusStopResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(31, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1773,7 +1926,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_FocusRange() { - ::grpc::Service::MarkMethodAsync(32); + ::grpc::Service::MarkMethodAsync(35); } ~WithAsyncMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); @@ -1784,50 +1937,23 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusRange(::grpc::ServerContext* context, ::mavsdk::rpc::camera::FocusRangeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::camera::FocusRangeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(32, context, request, response, new_call_cq, notification_cq, tag); - } - }; - typedef WithAsyncMethod_Prepare > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; - template - class WithCallbackMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_Prepare() { - ::grpc::Service::MarkMethodCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::PrepareRequest* request, ::mavsdk::rpc::camera::PrepareResponse* response) { return this->Prepare(context, request, response); }));} - void SetMessageAllocatorFor_Prepare( - ::grpc::MessageAllocator< ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } - // disable synchronous version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* Prepare( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) { return nullptr; } }; + typedef WithAsyncMethod_TakePhoto > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_TakePhoto() { - ::grpc::Service::MarkMethodCallback(1, + ::grpc::Service::MarkMethodCallback(0, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::TakePhotoRequest* request, ::mavsdk::rpc::camera::TakePhotoResponse* response) { return this->TakePhoto(context, request, response); }));} void SetMessageAllocatorFor_TakePhoto( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1848,13 +1974,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodCallback(2, + ::grpc::Service::MarkMethodCallback(1, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartPhotoIntervalRequest, ::mavsdk::rpc::camera::StartPhotoIntervalResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* request, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* response) { return this->StartPhotoInterval(context, request, response); }));} void SetMessageAllocatorFor_StartPhotoInterval( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StartPhotoIntervalRequest, ::mavsdk::rpc::camera::StartPhotoIntervalResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartPhotoIntervalRequest, ::mavsdk::rpc::camera::StartPhotoIntervalResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1875,13 +2001,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodCallback(3, + ::grpc::Service::MarkMethodCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopPhotoIntervalRequest, ::mavsdk::rpc::camera::StopPhotoIntervalResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StopPhotoIntervalRequest* request, ::mavsdk::rpc::camera::StopPhotoIntervalResponse* response) { return this->StopPhotoInterval(context, request, response); }));} void SetMessageAllocatorFor_StopPhotoInterval( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StopPhotoIntervalRequest, ::mavsdk::rpc::camera::StopPhotoIntervalResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopPhotoIntervalRequest, ::mavsdk::rpc::camera::StopPhotoIntervalResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1902,13 +2028,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StartVideo() { - ::grpc::Service::MarkMethodCallback(4, + ::grpc::Service::MarkMethodCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartVideoRequest, ::mavsdk::rpc::camera::StartVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StartVideoRequest* request, ::mavsdk::rpc::camera::StartVideoResponse* response) { return this->StartVideo(context, request, response); }));} void SetMessageAllocatorFor_StartVideo( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StartVideoRequest, ::mavsdk::rpc::camera::StartVideoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartVideoRequest, ::mavsdk::rpc::camera::StartVideoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1929,13 +2055,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StopVideo() { - ::grpc::Service::MarkMethodCallback(5, + ::grpc::Service::MarkMethodCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopVideoRequest, ::mavsdk::rpc::camera::StopVideoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StopVideoRequest* request, ::mavsdk::rpc::camera::StopVideoResponse* response) { return this->StopVideo(context, request, response); }));} void SetMessageAllocatorFor_StopVideo( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StopVideoRequest, ::mavsdk::rpc::camera::StopVideoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopVideoRequest, ::mavsdk::rpc::camera::StopVideoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1956,13 +2082,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartVideoStreamingRequest, ::mavsdk::rpc::camera::StartVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StartVideoStreamingRequest* request, ::mavsdk::rpc::camera::StartVideoStreamingResponse* response) { return this->StartVideoStreaming(context, request, response); }));} void SetMessageAllocatorFor_StartVideoStreaming( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StartVideoStreamingRequest, ::mavsdk::rpc::camera::StartVideoStreamingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StartVideoStreamingRequest, ::mavsdk::rpc::camera::StartVideoStreamingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -1983,13 +2109,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodCallback(7, + ::grpc::Service::MarkMethodCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopVideoStreamingRequest, ::mavsdk::rpc::camera::StopVideoStreamingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::StopVideoStreamingRequest* request, ::mavsdk::rpc::camera::StopVideoStreamingResponse* response) { return this->StopVideoStreaming(context, request, response); }));} void SetMessageAllocatorFor_StopVideoStreaming( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::StopVideoStreamingRequest, ::mavsdk::rpc::camera::StopVideoStreamingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::StopVideoStreamingRequest, ::mavsdk::rpc::camera::StopVideoStreamingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2010,13 +2136,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetMode() { - ::grpc::Service::MarkMethodCallback(8, + ::grpc::Service::MarkMethodCallback(7, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SetModeRequest, ::mavsdk::rpc::camera::SetModeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SetModeRequest* request, ::mavsdk::rpc::camera::SetModeResponse* response) { return this->SetMode(context, request, response); }));} void SetMessageAllocatorFor_SetMode( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::SetModeRequest, ::mavsdk::rpc::camera::SetModeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(8); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SetModeRequest, ::mavsdk::rpc::camera::SetModeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2037,13 +2163,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ListPhotos() { - ::grpc::Service::MarkMethodCallback(9, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ListPhotosRequest, ::mavsdk::rpc::camera::ListPhotosResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ListPhotosRequest* request, ::mavsdk::rpc::camera::ListPhotosResponse* response) { return this->ListPhotos(context, request, response); }));} void SetMessageAllocatorFor_ListPhotos( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ListPhotosRequest, ::mavsdk::rpc::camera::ListPhotosResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(9); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(8); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ListPhotosRequest, ::mavsdk::rpc::camera::ListPhotosResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2059,6 +2185,28 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ListPhotosRequest* /*request*/, ::mavsdk::rpc::camera::ListPhotosResponse* /*response*/) { return nullptr; } }; template + class WithCallbackMethod_SubscribeCameraList : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeCameraListRequest, ::mavsdk::rpc::camera::CameraListResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* request) { return this->SubscribeCameraList(context, request); })); + } + ~WithCallbackMethod_SubscribeCameraList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera::CameraListResponse>* SubscribeCameraList( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2081,26 +2229,31 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeModeRequest* /*request*/) { return nullptr; } }; template - class WithCallbackMethod_SubscribeInformation : public BaseClass { + class WithCallbackMethod_GetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_SubscribeInformation() { + WithCallbackMethod_GetMode() { ::grpc::Service::MarkMethodCallback(11, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeInformationRequest, ::mavsdk::rpc::camera::InformationResponse>( + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribeInformationRequest* request) { return this->SubscribeInformation(context, request); })); + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetModeRequest* request, ::mavsdk::rpc::camera::GetModeResponse* response) { return this->GetMode(context, request, response); }));} + void SetMessageAllocatorFor_GetMode( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(11); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithCallbackMethod_SubscribeInformation() override { + ~WithCallbackMethod_GetMode() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::camera::InformationResponse>* SubscribeInformation( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* GetMode( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) { return nullptr; } }; template class WithCallbackMethod_SubscribeVideoStreamInfo : public BaseClass { @@ -2125,12 +2278,39 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_GetVideoStreamInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetVideoStreamInfo() { + ::grpc::Service::MarkMethodCallback(13, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* request, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* response) { return this->GetVideoStreamInfo(context, request, response); }));} + void SetMessageAllocatorFor_GetVideoStreamInfo( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(13); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetVideoStreamInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetVideoStreamInfo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeCaptureInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeCaptureInfo() { - ::grpc::Service::MarkMethodCallback(13, + ::grpc::Service::MarkMethodCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest, ::mavsdk::rpc::camera::CaptureInfoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* request) { return this->SubscribeCaptureInfo(context, request); })); @@ -2152,7 +2332,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodCallback(14, + ::grpc::Service::MarkMethodCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeStatusRequest, ::mavsdk::rpc::camera::StatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribeStatusRequest* request) { return this->SubscribeStatus(context, request); })); @@ -2169,12 +2349,39 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeStatusRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetStatus() { + ::grpc::Service::MarkMethodCallback(16, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetStatusRequest* request, ::mavsdk::rpc::camera::GetStatusResponse* response) { return this->GetStatus(context, request, response); }));} + void SetMessageAllocatorFor_GetStatus( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(16); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetStatus( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribeCurrentSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodCallback(15, + ::grpc::Service::MarkMethodCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest, ::mavsdk::rpc::camera::CurrentSettingsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* request) { return this->SubscribeCurrentSettings(context, request); })); @@ -2191,12 +2398,39 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodCallback(18, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* request, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* response) { return this->GetCurrentSettings(context, request, response); }));} + void SetMessageAllocatorFor_GetCurrentSettings( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(18); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetCurrentSettings( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SubscribePossibleSettingOptions : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodCallback(16, + ::grpc::Service::MarkMethodCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest, ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* request) { return this->SubscribePossibleSettingOptions(context, request); })); @@ -2213,18 +2447,45 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_GetPossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodCallback(20, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* request, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* response) { return this->GetPossibleSettingOptions(context, request, response); }));} + void SetMessageAllocatorFor_GetPossibleSettingOptions( + ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(20); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetPossibleSettingOptions() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetPossibleSettingOptions( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_SetSetting : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetSetting() { - ::grpc::Service::MarkMethodCallback(17, + ::grpc::Service::MarkMethodCallback(21, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SetSettingRequest* request, ::mavsdk::rpc::camera::SetSettingResponse* response) { return this->SetSetting(context, request, response); }));} void SetMessageAllocatorFor_SetSetting( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(17); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(21); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2245,13 +2506,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_GetSetting() { - ::grpc::Service::MarkMethodCallback(18, + ::grpc::Service::MarkMethodCallback(22, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetSettingRequest, ::mavsdk::rpc::camera::GetSettingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::GetSettingRequest* request, ::mavsdk::rpc::camera::GetSettingResponse* response) { return this->GetSetting(context, request, response); }));} void SetMessageAllocatorFor_GetSetting( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::GetSettingRequest, ::mavsdk::rpc::camera::GetSettingResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(18); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(22); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::GetSettingRequest, ::mavsdk::rpc::camera::GetSettingResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2272,13 +2533,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_FormatStorage() { - ::grpc::Service::MarkMethodCallback(19, + ::grpc::Service::MarkMethodCallback(23, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FormatStorageRequest, ::mavsdk::rpc::camera::FormatStorageResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::FormatStorageRequest* request, ::mavsdk::rpc::camera::FormatStorageResponse* response) { return this->FormatStorage(context, request, response); }));} void SetMessageAllocatorFor_FormatStorage( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::FormatStorageRequest, ::mavsdk::rpc::camera::FormatStorageResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(19); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(23); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FormatStorageRequest, ::mavsdk::rpc::camera::FormatStorageResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2294,45 +2555,18 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::FormatStorageRequest* /*request*/, ::mavsdk::rpc::camera::FormatStorageResponse* /*response*/) { return nullptr; } }; template - class WithCallbackMethod_SelectCamera : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SelectCamera() { - ::grpc::Service::MarkMethodCallback(20, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response) { return this->SelectCamera(context, request, response); }));} - void SetMessageAllocatorFor_SelectCamera( - ::grpc::MessageAllocator< ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(20); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_SelectCamera() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SelectCamera( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) { return nullptr; } - }; - template class WithCallbackMethod_ResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ResetSettings() { - ::grpc::Service::MarkMethodCallback(21, + ::grpc::Service::MarkMethodCallback(24, 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); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(24); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2353,13 +2587,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ZoomInStart() { - ::grpc::Service::MarkMethodCallback(22, + ::grpc::Service::MarkMethodCallback(25, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response) { return this->ZoomInStart(context, request, response); }));} void SetMessageAllocatorFor_ZoomInStart( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(22); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(25); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2380,13 +2614,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodCallback(23, + ::grpc::Service::MarkMethodCallback(26, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response) { return this->ZoomOutStart(context, request, response); }));} void SetMessageAllocatorFor_ZoomOutStart( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(23); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(26); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2407,13 +2641,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ZoomStop() { - ::grpc::Service::MarkMethodCallback(24, + ::grpc::Service::MarkMethodCallback(27, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response) { return this->ZoomStop(context, request, response); }));} void SetMessageAllocatorFor_ZoomStop( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(24); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(27); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2434,13 +2668,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ZoomRange() { - ::grpc::Service::MarkMethodCallback(25, + ::grpc::Service::MarkMethodCallback(28, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response) { return this->ZoomRange(context, request, response); }));} void SetMessageAllocatorFor_ZoomRange( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(25); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(28); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2461,13 +2695,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_TrackPoint() { - ::grpc::Service::MarkMethodCallback(26, + ::grpc::Service::MarkMethodCallback(29, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response) { return this->TrackPoint(context, request, response); }));} void SetMessageAllocatorFor_TrackPoint( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(26); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(29); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2488,13 +2722,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_TrackRectangle() { - ::grpc::Service::MarkMethodCallback(27, + ::grpc::Service::MarkMethodCallback(30, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response) { return this->TrackRectangle(context, request, response); }));} void SetMessageAllocatorFor_TrackRectangle( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(27); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(30); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2515,13 +2749,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_TrackStop() { - ::grpc::Service::MarkMethodCallback(28, + ::grpc::Service::MarkMethodCallback(31, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response) { return this->TrackStop(context, request, response); }));} void SetMessageAllocatorFor_TrackStop( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(28); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(31); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2542,13 +2776,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_FocusInStart() { - ::grpc::Service::MarkMethodCallback(29, + ::grpc::Service::MarkMethodCallback(32, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response) { return this->FocusInStart(context, request, response); }));} void SetMessageAllocatorFor_FocusInStart( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(29); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(32); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2569,13 +2803,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_FocusOutStart() { - ::grpc::Service::MarkMethodCallback(30, + ::grpc::Service::MarkMethodCallback(33, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response) { return this->FocusOutStart(context, request, response); }));} void SetMessageAllocatorFor_FocusOutStart( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(30); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(33); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2596,13 +2830,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_FocusStop() { - ::grpc::Service::MarkMethodCallback(31, + ::grpc::Service::MarkMethodCallback(34, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response) { return this->FocusStop(context, request, response); }));} void SetMessageAllocatorFor_FocusStop( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(31); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(34); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2623,13 +2857,13 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_FocusRange() { - ::grpc::Service::MarkMethodCallback(32, + ::grpc::Service::MarkMethodCallback(35, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response) { return this->FocusRange(context, request, response); }));} void SetMessageAllocatorFor_FocusRange( ::grpc::MessageAllocator< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(32); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(35); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -2644,32 +2878,15 @@ class CameraService final { virtual ::grpc::ServerUnaryReactor* FocusRange( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_Prepare > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > CallbackService; + typedef WithCallbackMethod_TakePhoto > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template - class WithGenericMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_Prepare() { - ::grpc::Service::MarkMethodGeneric(0); - } - ~WithGenericMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithGenericMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_TakePhoto() { - ::grpc::Service::MarkMethodGeneric(1); + ::grpc::Service::MarkMethodGeneric(0); } ~WithGenericMethod_TakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -2686,7 +2903,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodGeneric(2); + ::grpc::Service::MarkMethodGeneric(1); } ~WithGenericMethod_StartPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -2703,7 +2920,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodGeneric(3); + ::grpc::Service::MarkMethodGeneric(2); } ~WithGenericMethod_StopPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -2720,7 +2937,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StartVideo() { - ::grpc::Service::MarkMethodGeneric(4); + ::grpc::Service::MarkMethodGeneric(3); } ~WithGenericMethod_StartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2737,7 +2954,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StopVideo() { - ::grpc::Service::MarkMethodGeneric(5); + ::grpc::Service::MarkMethodGeneric(4); } ~WithGenericMethod_StopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -2754,7 +2971,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(5); } ~WithGenericMethod_StartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2771,7 +2988,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(6); } ~WithGenericMethod_StopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -2788,7 +3005,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetMode() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(7); } ~WithGenericMethod_SetMode() override { BaseClassMustBeDerivedFromService(this); @@ -2805,7 +3022,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ListPhotos() { - ::grpc::Service::MarkMethodGeneric(9); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_ListPhotos() override { BaseClassMustBeDerivedFromService(this); @@ -2817,6 +3034,23 @@ class CameraService final { } }; template + class WithGenericMethod_SubscribeCameraList : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodGeneric(9); + } + ~WithGenericMethod_SubscribeCameraList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2834,18 +3068,18 @@ class CameraService final { } }; template - class WithGenericMethod_SubscribeInformation : public BaseClass { + class WithGenericMethod_GetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SubscribeInformation() { + WithGenericMethod_GetMode() { ::grpc::Service::MarkMethodGeneric(11); } - ~WithGenericMethod_SubscribeInformation() override { + ~WithGenericMethod_GetMode() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -2868,18 +3102,35 @@ class CameraService final { } }; template - class WithGenericMethod_SubscribeCaptureInfo : public BaseClass { + class WithGenericMethod_GetVideoStreamInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SubscribeCaptureInfo() { + WithGenericMethod_GetVideoStreamInfo() { ::grpc::Service::MarkMethodGeneric(13); } - ~WithGenericMethod_SubscribeCaptureInfo() override { + ~WithGenericMethod_GetVideoStreamInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeCaptureInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CaptureInfoResponse>* /*writer*/) override { + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeCaptureInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeCaptureInfo() { + ::grpc::Service::MarkMethodGeneric(14); + } + ~WithGenericMethod_SubscribeCaptureInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCaptureInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CaptureInfoResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -2890,7 +3141,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodGeneric(14); + ::grpc::Service::MarkMethodGeneric(15); } ~WithGenericMethod_SubscribeStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2902,12 +3153,29 @@ class CameraService final { } }; template + class WithGenericMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetStatus() { + ::grpc::Service::MarkMethodGeneric(16); + } + ~WithGenericMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeCurrentSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodGeneric(15); + ::grpc::Service::MarkMethodGeneric(17); } ~WithGenericMethod_SubscribeCurrentSettings() override { BaseClassMustBeDerivedFromService(this); @@ -2919,12 +3187,29 @@ class CameraService final { } }; template + class WithGenericMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodGeneric(18); + } + ~WithGenericMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribePossibleSettingOptions : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodGeneric(16); + ::grpc::Service::MarkMethodGeneric(19); } ~WithGenericMethod_SubscribePossibleSettingOptions() override { BaseClassMustBeDerivedFromService(this); @@ -2936,69 +3221,69 @@ class CameraService final { } }; template - class WithGenericMethod_SetSetting : public BaseClass { + class WithGenericMethod_GetPossibleSettingOptions : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SetSetting() { - ::grpc::Service::MarkMethodGeneric(17); + WithGenericMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodGeneric(20); } - ~WithGenericMethod_SetSetting() override { + ~WithGenericMethod_GetPossibleSettingOptions() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetSetting(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SetSettingRequest* /*request*/, ::mavsdk::rpc::camera::SetSettingResponse* /*response*/) override { + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } }; template - class WithGenericMethod_GetSetting : public BaseClass { + class WithGenericMethod_SetSetting : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_GetSetting() { - ::grpc::Service::MarkMethodGeneric(18); + WithGenericMethod_SetSetting() { + ::grpc::Service::MarkMethodGeneric(21); } - ~WithGenericMethod_GetSetting() override { + ~WithGenericMethod_SetSetting() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status GetSetting(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetSettingRequest* /*request*/, ::mavsdk::rpc::camera::GetSettingResponse* /*response*/) override { + ::grpc::Status SetSetting(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SetSettingRequest* /*request*/, ::mavsdk::rpc::camera::SetSettingResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } }; template - class WithGenericMethod_FormatStorage : public BaseClass { + class WithGenericMethod_GetSetting : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_FormatStorage() { - ::grpc::Service::MarkMethodGeneric(19); + WithGenericMethod_GetSetting() { + ::grpc::Service::MarkMethodGeneric(22); } - ~WithGenericMethod_FormatStorage() override { + ~WithGenericMethod_GetSetting() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status FormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FormatStorageRequest* /*request*/, ::mavsdk::rpc::camera::FormatStorageResponse* /*response*/) override { + ::grpc::Status GetSetting(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetSettingRequest* /*request*/, ::mavsdk::rpc::camera::GetSettingResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } }; template - class WithGenericMethod_SelectCamera : public BaseClass { + class WithGenericMethod_FormatStorage : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SelectCamera() { - ::grpc::Service::MarkMethodGeneric(20); + WithGenericMethod_FormatStorage() { + ::grpc::Service::MarkMethodGeneric(23); } - ~WithGenericMethod_SelectCamera() override { + ~WithGenericMethod_FormatStorage() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { + ::grpc::Status FormatStorage(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FormatStorageRequest* /*request*/, ::mavsdk::rpc::camera::FormatStorageResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -3009,7 +3294,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ResetSettings() { - ::grpc::Service::MarkMethodGeneric(21); + ::grpc::Service::MarkMethodGeneric(24); } ~WithGenericMethod_ResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -3026,7 +3311,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ZoomInStart() { - ::grpc::Service::MarkMethodGeneric(22); + ::grpc::Service::MarkMethodGeneric(25); } ~WithGenericMethod_ZoomInStart() override { BaseClassMustBeDerivedFromService(this); @@ -3043,7 +3328,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodGeneric(23); + ::grpc::Service::MarkMethodGeneric(26); } ~WithGenericMethod_ZoomOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -3060,7 +3345,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ZoomStop() { - ::grpc::Service::MarkMethodGeneric(24); + ::grpc::Service::MarkMethodGeneric(27); } ~WithGenericMethod_ZoomStop() override { BaseClassMustBeDerivedFromService(this); @@ -3077,7 +3362,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ZoomRange() { - ::grpc::Service::MarkMethodGeneric(25); + ::grpc::Service::MarkMethodGeneric(28); } ~WithGenericMethod_ZoomRange() override { BaseClassMustBeDerivedFromService(this); @@ -3094,7 +3379,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_TrackPoint() { - ::grpc::Service::MarkMethodGeneric(26); + ::grpc::Service::MarkMethodGeneric(29); } ~WithGenericMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); @@ -3111,7 +3396,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_TrackRectangle() { - ::grpc::Service::MarkMethodGeneric(27); + ::grpc::Service::MarkMethodGeneric(30); } ~WithGenericMethod_TrackRectangle() override { BaseClassMustBeDerivedFromService(this); @@ -3128,7 +3413,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_TrackStop() { - ::grpc::Service::MarkMethodGeneric(28); + ::grpc::Service::MarkMethodGeneric(31); } ~WithGenericMethod_TrackStop() override { BaseClassMustBeDerivedFromService(this); @@ -3145,7 +3430,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_FocusInStart() { - ::grpc::Service::MarkMethodGeneric(29); + ::grpc::Service::MarkMethodGeneric(32); } ~WithGenericMethod_FocusInStart() override { BaseClassMustBeDerivedFromService(this); @@ -3162,7 +3447,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_FocusOutStart() { - ::grpc::Service::MarkMethodGeneric(30); + ::grpc::Service::MarkMethodGeneric(33); } ~WithGenericMethod_FocusOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -3179,7 +3464,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_FocusStop() { - ::grpc::Service::MarkMethodGeneric(31); + ::grpc::Service::MarkMethodGeneric(34); } ~WithGenericMethod_FocusStop() override { BaseClassMustBeDerivedFromService(this); @@ -3196,7 +3481,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_FocusRange() { - ::grpc::Service::MarkMethodGeneric(32); + ::grpc::Service::MarkMethodGeneric(35); } ~WithGenericMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); @@ -3208,32 +3493,12 @@ class CameraService final { } }; template - class WithRawMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_Prepare() { - ::grpc::Service::MarkMethodRaw(0); - } - ~WithRawMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestPrepare(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template class WithRawMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_TakePhoto() { - ::grpc::Service::MarkMethodRaw(1); + ::grpc::Service::MarkMethodRaw(0); } ~WithRawMethod_TakePhoto() override { BaseClassMustBeDerivedFromService(this); @@ -3244,7 +3509,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTakePhoto(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3253,7 +3518,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodRaw(2); + ::grpc::Service::MarkMethodRaw(1); } ~WithRawMethod_StartPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -3264,7 +3529,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartPhotoInterval(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3273,7 +3538,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodRaw(3); + ::grpc::Service::MarkMethodRaw(2); } ~WithRawMethod_StopPhotoInterval() override { BaseClassMustBeDerivedFromService(this); @@ -3284,7 +3549,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopPhotoInterval(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3293,7 +3558,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StartVideo() { - ::grpc::Service::MarkMethodRaw(4); + ::grpc::Service::MarkMethodRaw(3); } ~WithRawMethod_StartVideo() override { BaseClassMustBeDerivedFromService(this); @@ -3304,7 +3569,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartVideo(::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(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3313,7 +3578,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StopVideo() { - ::grpc::Service::MarkMethodRaw(5); + ::grpc::Service::MarkMethodRaw(4); } ~WithRawMethod_StopVideo() override { BaseClassMustBeDerivedFromService(this); @@ -3324,7 +3589,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopVideo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3333,7 +3598,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(5); } ~WithRawMethod_StartVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -3344,7 +3609,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStartVideoStreaming(::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(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3353,7 +3618,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(6); } ~WithRawMethod_StopVideoStreaming() override { BaseClassMustBeDerivedFromService(this); @@ -3364,7 +3629,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestStopVideoStreaming(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3373,7 +3638,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetMode() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(7); } ~WithRawMethod_SetMode() override { BaseClassMustBeDerivedFromService(this); @@ -3384,7 +3649,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetMode(::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(8, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3393,7 +3658,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ListPhotos() { - ::grpc::Service::MarkMethodRaw(9); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_ListPhotos() override { BaseClassMustBeDerivedFromService(this); @@ -3404,7 +3669,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestListPhotos(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(8, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeCameraList : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_SubscribeCameraList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeCameraList(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -3428,23 +3713,23 @@ class CameraService final { } }; template - class WithRawMethod_SubscribeInformation : public BaseClass { + class WithRawMethod_GetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SubscribeInformation() { + WithRawMethod_GetMode() { ::grpc::Service::MarkMethodRaw(11); } - ~WithRawMethod_SubscribeInformation() override { + ~WithRawMethod_GetMode() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSubscribeInformation(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + void RequestGetMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(11, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3468,12 +3753,32 @@ class CameraService final { } }; template + class WithRawMethod_GetVideoStreamInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetVideoStreamInfo() { + ::grpc::Service::MarkMethodRaw(13); + } + ~WithRawMethod_GetVideoStreamInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetVideoStreamInfo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(13, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_SubscribeCaptureInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeCaptureInfo() { - ::grpc::Service::MarkMethodRaw(13); + ::grpc::Service::MarkMethodRaw(14); } ~WithRawMethod_SubscribeCaptureInfo() override { BaseClassMustBeDerivedFromService(this); @@ -3484,7 +3789,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCaptureInfo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -3493,7 +3798,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodRaw(14); + ::grpc::Service::MarkMethodRaw(15); } ~WithRawMethod_SubscribeStatus() override { BaseClassMustBeDerivedFromService(this); @@ -3504,7 +3809,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetStatus() { + ::grpc::Service::MarkMethodRaw(16); + } + ~WithRawMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetStatus(::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(16, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3513,7 +3838,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodRaw(15); + ::grpc::Service::MarkMethodRaw(17); } ~WithRawMethod_SubscribeCurrentSettings() override { BaseClassMustBeDerivedFromService(this); @@ -3524,7 +3849,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCurrentSettings(::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(15, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodRaw(18); + } + ~WithRawMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetCurrentSettings(::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(18, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3533,7 +3878,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodRaw(16); + ::grpc::Service::MarkMethodRaw(19); } ~WithRawMethod_SubscribePossibleSettingOptions() override { BaseClassMustBeDerivedFromService(this); @@ -3544,7 +3889,27 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribePossibleSettingOptions(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetPossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodRaw(20); + } + ~WithRawMethod_GetPossibleSettingOptions() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetPossibleSettingOptions(::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(20, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3553,7 +3918,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetSetting() { - ::grpc::Service::MarkMethodRaw(17); + ::grpc::Service::MarkMethodRaw(21); } ~WithRawMethod_SetSetting() override { BaseClassMustBeDerivedFromService(this); @@ -3564,7 +3929,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetSetting(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(17, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3573,7 +3938,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_GetSetting() { - ::grpc::Service::MarkMethodRaw(18); + ::grpc::Service::MarkMethodRaw(22); } ~WithRawMethod_GetSetting() override { BaseClassMustBeDerivedFromService(this); @@ -3584,7 +3949,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestGetSetting(::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(18, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(22, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3593,7 +3958,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_FormatStorage() { - ::grpc::Service::MarkMethodRaw(19); + ::grpc::Service::MarkMethodRaw(23); } ~WithRawMethod_FormatStorage() override { BaseClassMustBeDerivedFromService(this); @@ -3604,27 +3969,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFormatStorage(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(19, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SelectCamera : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SelectCamera() { - ::grpc::Service::MarkMethodRaw(20); - } - ~WithRawMethod_SelectCamera() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSelectCamera(::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(20, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(23, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3633,7 +3978,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ResetSettings() { - ::grpc::Service::MarkMethodRaw(21); + ::grpc::Service::MarkMethodRaw(24); } ~WithRawMethod_ResetSettings() override { BaseClassMustBeDerivedFromService(this); @@ -3644,7 +3989,7 @@ class CameraService final { 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); + ::grpc::Service::RequestAsyncUnary(24, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3653,7 +3998,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ZoomInStart() { - ::grpc::Service::MarkMethodRaw(22); + ::grpc::Service::MarkMethodRaw(25); } ~WithRawMethod_ZoomInStart() override { BaseClassMustBeDerivedFromService(this); @@ -3664,7 +4009,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomInStart(::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(22, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(25, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3673,7 +4018,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodRaw(23); + ::grpc::Service::MarkMethodRaw(26); } ~WithRawMethod_ZoomOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -3684,7 +4029,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomOutStart(::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(23, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(26, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3693,7 +4038,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ZoomStop() { - ::grpc::Service::MarkMethodRaw(24); + ::grpc::Service::MarkMethodRaw(27); } ~WithRawMethod_ZoomStop() override { BaseClassMustBeDerivedFromService(this); @@ -3704,7 +4049,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomStop(::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(24, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(27, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3713,7 +4058,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ZoomRange() { - ::grpc::Service::MarkMethodRaw(25); + ::grpc::Service::MarkMethodRaw(28); } ~WithRawMethod_ZoomRange() override { BaseClassMustBeDerivedFromService(this); @@ -3724,7 +4069,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestZoomRange(::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(25, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(28, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3733,7 +4078,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_TrackPoint() { - ::grpc::Service::MarkMethodRaw(26); + ::grpc::Service::MarkMethodRaw(29); } ~WithRawMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); @@ -3744,7 +4089,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackPoint(::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(26, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(29, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3753,7 +4098,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_TrackRectangle() { - ::grpc::Service::MarkMethodRaw(27); + ::grpc::Service::MarkMethodRaw(30); } ~WithRawMethod_TrackRectangle() override { BaseClassMustBeDerivedFromService(this); @@ -3764,7 +4109,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackRectangle(::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(27, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(30, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3773,7 +4118,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_TrackStop() { - ::grpc::Service::MarkMethodRaw(28); + ::grpc::Service::MarkMethodRaw(31); } ~WithRawMethod_TrackStop() override { BaseClassMustBeDerivedFromService(this); @@ -3784,7 +4129,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestTrackStop(::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(28, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(31, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3793,7 +4138,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_FocusInStart() { - ::grpc::Service::MarkMethodRaw(29); + ::grpc::Service::MarkMethodRaw(32); } ~WithRawMethod_FocusInStart() override { BaseClassMustBeDerivedFromService(this); @@ -3804,7 +4149,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusInStart(::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(29, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(32, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3813,7 +4158,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_FocusOutStart() { - ::grpc::Service::MarkMethodRaw(30); + ::grpc::Service::MarkMethodRaw(33); } ~WithRawMethod_FocusOutStart() override { BaseClassMustBeDerivedFromService(this); @@ -3824,7 +4169,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusOutStart(::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(30, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(33, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3833,7 +4178,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_FocusStop() { - ::grpc::Service::MarkMethodRaw(31); + ::grpc::Service::MarkMethodRaw(34); } ~WithRawMethod_FocusStop() override { BaseClassMustBeDerivedFromService(this); @@ -3844,7 +4189,7 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusStop(::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(31, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -3853,7 +4198,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_FocusRange() { - ::grpc::Service::MarkMethodRaw(32); + ::grpc::Service::MarkMethodRaw(35); } ~WithRawMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); @@ -3864,38 +4209,16 @@ class CameraService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestFocusRange(::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(32, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } }; template - class WithRawCallbackMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_Prepare() { - ::grpc::Service::MarkMethodRawCallback(0, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->Prepare(context, request, response); })); - } - ~WithRawCallbackMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* Prepare( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template class WithRawCallbackMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_TakePhoto() { - ::grpc::Service::MarkMethodRawCallback(1, + ::grpc::Service::MarkMethodRawCallback(0, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TakePhoto(context, request, response); })); @@ -3917,7 +4240,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodRawCallback(2, + ::grpc::Service::MarkMethodRawCallback(1, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StartPhotoInterval(context, request, response); })); @@ -3939,7 +4262,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodRawCallback(3, + ::grpc::Service::MarkMethodRawCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StopPhotoInterval(context, request, response); })); @@ -3961,7 +4284,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StartVideo() { - ::grpc::Service::MarkMethodRawCallback(4, + ::grpc::Service::MarkMethodRawCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StartVideo(context, request, response); })); @@ -3983,7 +4306,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StopVideo() { - ::grpc::Service::MarkMethodRawCallback(5, + ::grpc::Service::MarkMethodRawCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StopVideo(context, request, response); })); @@ -4005,7 +4328,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(6, + ::grpc::Service::MarkMethodRawCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StartVideoStreaming(context, request, response); })); @@ -4027,7 +4350,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodRawCallback(7, + ::grpc::Service::MarkMethodRawCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->StopVideoStreaming(context, request, response); })); @@ -4049,7 +4372,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetMode() { - ::grpc::Service::MarkMethodRawCallback(8, + ::grpc::Service::MarkMethodRawCallback(7, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetMode(context, request, response); })); @@ -4071,7 +4394,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ListPhotos() { - ::grpc::Service::MarkMethodRawCallback(9, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ListPhotos(context, request, response); })); @@ -4088,6 +4411,28 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeCameraList : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodRawCallback(9, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCameraList(context, request); })); + } + ~WithRawCallbackMethod_SubscribeCameraList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCameraList( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -4110,26 +4455,26 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template - class WithRawCallbackMethod_SubscribeInformation : public BaseClass { + class WithRawCallbackMethod_GetMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SubscribeInformation() { + WithRawCallbackMethod_GetMode() { ::grpc::Service::MarkMethodRawCallback(11, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeInformation(context, request); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetMode(context, request, response); })); } - ~WithRawCallbackMethod_SubscribeInformation() override { + ~WithRawCallbackMethod_GetMode() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeInformation( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* GetMode( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template class WithRawCallbackMethod_SubscribeVideoStreamInfo : public BaseClass { @@ -4154,12 +4499,34 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_GetVideoStreamInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetVideoStreamInfo() { + ::grpc::Service::MarkMethodRawCallback(13, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetVideoStreamInfo(context, request, response); })); + } + ~WithRawCallbackMethod_GetVideoStreamInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetVideoStreamInfo( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeCaptureInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeCaptureInfo() { - ::grpc::Service::MarkMethodRawCallback(13, + ::grpc::Service::MarkMethodRawCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCaptureInfo(context, request); })); @@ -4181,7 +4548,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodRawCallback(14, + ::grpc::Service::MarkMethodRawCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStatus(context, request); })); @@ -4198,12 +4565,34 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetStatus() { + ::grpc::Service::MarkMethodRawCallback(16, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetStatus(context, request, response); })); + } + ~WithRawCallbackMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetStatus( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeCurrentSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodRawCallback(15, + ::grpc::Service::MarkMethodRawCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCurrentSettings(context, request); })); @@ -4220,26 +4609,70 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodRawCallback(18, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetCurrentSettings(context, request, response); })); + } + ~WithRawCallbackMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetCurrentSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribePossibleSettingOptions : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodRawCallback(16, + ::grpc::Service::MarkMethodRawCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribePossibleSettingOptions(context, request); })); + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribePossibleSettingOptions(context, request); })); + } + ~WithRawCallbackMethod_SubscribePossibleSettingOptions() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribePossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribePossibleSettingOptions( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_GetPossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodRawCallback(20, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetPossibleSettingOptions(context, request, response); })); } - ~WithRawCallbackMethod_SubscribePossibleSettingOptions() override { + ~WithRawCallbackMethod_GetPossibleSettingOptions() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribePossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* /*writer*/) override { + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribePossibleSettingOptions( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* GetPossibleSettingOptions( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template class WithRawCallbackMethod_SetSetting : public BaseClass { @@ -4247,7 +4680,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetSetting() { - ::grpc::Service::MarkMethodRawCallback(17, + ::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->SetSetting(context, request, response); })); @@ -4269,7 +4702,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_GetSetting() { - ::grpc::Service::MarkMethodRawCallback(18, + ::grpc::Service::MarkMethodRawCallback(22, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetSetting(context, request, response); })); @@ -4291,7 +4724,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_FormatStorage() { - ::grpc::Service::MarkMethodRawCallback(19, + ::grpc::Service::MarkMethodRawCallback(23, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FormatStorage(context, request, response); })); @@ -4308,34 +4741,12 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SelectCamera : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SelectCamera() { - ::grpc::Service::MarkMethodRawCallback(20, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SelectCamera(context, request, response); })); - } - ~WithRawCallbackMethod_SelectCamera() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SelectCamera( - ::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, + ::grpc::Service::MarkMethodRawCallback(24, 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); })); @@ -4357,7 +4768,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ZoomInStart() { - ::grpc::Service::MarkMethodRawCallback(22, + ::grpc::Service::MarkMethodRawCallback(25, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ZoomInStart(context, request, response); })); @@ -4379,7 +4790,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodRawCallback(23, + ::grpc::Service::MarkMethodRawCallback(26, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ZoomOutStart(context, request, response); })); @@ -4401,7 +4812,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ZoomStop() { - ::grpc::Service::MarkMethodRawCallback(24, + ::grpc::Service::MarkMethodRawCallback(27, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ZoomStop(context, request, response); })); @@ -4423,7 +4834,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ZoomRange() { - ::grpc::Service::MarkMethodRawCallback(25, + ::grpc::Service::MarkMethodRawCallback(28, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ZoomRange(context, request, response); })); @@ -4445,7 +4856,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_TrackPoint() { - ::grpc::Service::MarkMethodRawCallback(26, + ::grpc::Service::MarkMethodRawCallback(29, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackPoint(context, request, response); })); @@ -4467,7 +4878,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_TrackRectangle() { - ::grpc::Service::MarkMethodRawCallback(27, + ::grpc::Service::MarkMethodRawCallback(30, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackRectangle(context, request, response); })); @@ -4489,7 +4900,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_TrackStop() { - ::grpc::Service::MarkMethodRawCallback(28, + ::grpc::Service::MarkMethodRawCallback(31, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackStop(context, request, response); })); @@ -4511,7 +4922,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_FocusInStart() { - ::grpc::Service::MarkMethodRawCallback(29, + ::grpc::Service::MarkMethodRawCallback(32, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusInStart(context, request, response); })); @@ -4533,7 +4944,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_FocusOutStart() { - ::grpc::Service::MarkMethodRawCallback(30, + ::grpc::Service::MarkMethodRawCallback(33, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusOutStart(context, request, response); })); @@ -4555,7 +4966,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_FocusStop() { - ::grpc::Service::MarkMethodRawCallback(31, + ::grpc::Service::MarkMethodRawCallback(34, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusStop(context, request, response); })); @@ -4577,7 +4988,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_FocusRange() { - ::grpc::Service::MarkMethodRawCallback(32, + ::grpc::Service::MarkMethodRawCallback(35, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusRange(context, request, response); })); @@ -4594,39 +5005,12 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithStreamedUnaryMethod_Prepare : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_Prepare() { - ::grpc::Service::MarkMethodStreamed(0, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::camera::PrepareRequest, ::mavsdk::rpc::camera::PrepareResponse>* streamer) { - return this->StreamedPrepare(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_Prepare() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status Prepare(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::PrepareRequest* /*request*/, ::mavsdk::rpc::camera::PrepareResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedPrepare(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::PrepareRequest,::mavsdk::rpc::camera::PrepareResponse>* server_unary_streamer) = 0; - }; - template class WithStreamedUnaryMethod_TakePhoto : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_TakePhoto() { - ::grpc::Service::MarkMethodStreamed(1, + ::grpc::Service::MarkMethodStreamed(0, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::TakePhotoRequest, ::mavsdk::rpc::camera::TakePhotoResponse>( [this](::grpc::ServerContext* context, @@ -4653,7 +5037,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodStreamed(2, + ::grpc::Service::MarkMethodStreamed(1, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StartPhotoIntervalRequest, ::mavsdk::rpc::camera::StartPhotoIntervalResponse>( [this](::grpc::ServerContext* context, @@ -4680,7 +5064,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodStreamed(3, + ::grpc::Service::MarkMethodStreamed(2, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StopPhotoIntervalRequest, ::mavsdk::rpc::camera::StopPhotoIntervalResponse>( [this](::grpc::ServerContext* context, @@ -4707,7 +5091,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StartVideo() { - ::grpc::Service::MarkMethodStreamed(4, + ::grpc::Service::MarkMethodStreamed(3, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StartVideoRequest, ::mavsdk::rpc::camera::StartVideoResponse>( [this](::grpc::ServerContext* context, @@ -4734,7 +5118,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StopVideo() { - ::grpc::Service::MarkMethodStreamed(5, + ::grpc::Service::MarkMethodStreamed(4, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StopVideoRequest, ::mavsdk::rpc::camera::StopVideoResponse>( [this](::grpc::ServerContext* context, @@ -4761,7 +5145,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(5, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StartVideoStreamingRequest, ::mavsdk::rpc::camera::StartVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -4788,7 +5172,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(6, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::StopVideoStreamingRequest, ::mavsdk::rpc::camera::StopVideoStreamingResponse>( [this](::grpc::ServerContext* context, @@ -4815,7 +5199,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetMode() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(7, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::SetModeRequest, ::mavsdk::rpc::camera::SetModeResponse>( [this](::grpc::ServerContext* context, @@ -4842,7 +5226,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ListPhotos() { - ::grpc::Service::MarkMethodStreamed(9, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ListPhotosRequest, ::mavsdk::rpc::camera::ListPhotosResponse>( [this](::grpc::ServerContext* context, @@ -4864,12 +5248,147 @@ class CameraService final { virtual ::grpc::Status StreamedListPhotos(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ListPhotosRequest,::mavsdk::rpc::camera::ListPhotosResponse>* server_unary_streamer) = 0; }; template + class WithStreamedUnaryMethod_GetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetMode() { + ::grpc::Service::MarkMethodStreamed(11, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::GetModeRequest, ::mavsdk::rpc::camera::GetModeResponse>* streamer) { + return this->StreamedGetMode(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetModeRequest* /*request*/, ::mavsdk::rpc::camera::GetModeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetMode(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::GetModeRequest,::mavsdk::rpc::camera::GetModeResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetVideoStreamInfo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetVideoStreamInfo() { + ::grpc::Service::MarkMethodStreamed(13, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::GetVideoStreamInfoRequest, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* streamer) { + return this->StreamedGetVideoStreamInfo(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetVideoStreamInfo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetVideoStreamInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetVideoStreamInfoRequest* /*request*/, ::mavsdk::rpc::camera::GetVideoStreamInfoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetVideoStreamInfo(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::GetVideoStreamInfoRequest,::mavsdk::rpc::camera::GetVideoStreamInfoResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetStatus() { + ::grpc::Service::MarkMethodStreamed(16, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::GetStatusRequest, ::mavsdk::rpc::camera::GetStatusResponse>* streamer) { + return this->StreamedGetStatus(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetStatusRequest* /*request*/, ::mavsdk::rpc::camera::GetStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetStatus(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::GetStatusRequest,::mavsdk::rpc::camera::GetStatusResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetCurrentSettings() { + ::grpc::Service::MarkMethodStreamed(18, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::GetCurrentSettingsRequest, ::mavsdk::rpc::camera::GetCurrentSettingsResponse>* streamer) { + return this->StreamedGetCurrentSettings(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetCurrentSettingsRequest* /*request*/, ::mavsdk::rpc::camera::GetCurrentSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetCurrentSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::GetCurrentSettingsRequest,::mavsdk::rpc::camera::GetCurrentSettingsResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetPossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetPossibleSettingOptions() { + ::grpc::Service::MarkMethodStreamed(20, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* streamer) { + return this->StreamedGetPossibleSettingOptions(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetPossibleSettingOptions() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetPossibleSettingOptions(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest* /*request*/, ::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetPossibleSettingOptions(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest,::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse>* server_unary_streamer) = 0; + }; + template class WithStreamedUnaryMethod_SetSetting : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetSetting() { - ::grpc::Service::MarkMethodStreamed(17, + ::grpc::Service::MarkMethodStreamed(21, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::SetSettingRequest, ::mavsdk::rpc::camera::SetSettingResponse>( [this](::grpc::ServerContext* context, @@ -4896,7 +5415,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_GetSetting() { - ::grpc::Service::MarkMethodStreamed(18, + ::grpc::Service::MarkMethodStreamed(22, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::GetSettingRequest, ::mavsdk::rpc::camera::GetSettingResponse>( [this](::grpc::ServerContext* context, @@ -4923,7 +5442,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_FormatStorage() { - ::grpc::Service::MarkMethodStreamed(19, + ::grpc::Service::MarkMethodStreamed(23, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::FormatStorageRequest, ::mavsdk::rpc::camera::FormatStorageResponse>( [this](::grpc::ServerContext* context, @@ -4945,39 +5464,12 @@ class CameraService final { virtual ::grpc::Status StreamedFormatStorage(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::FormatStorageRequest,::mavsdk::rpc::camera::FormatStorageResponse>* server_unary_streamer) = 0; }; template - class WithStreamedUnaryMethod_SelectCamera : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_SelectCamera() { - ::grpc::Service::MarkMethodStreamed(20, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::camera::SelectCameraRequest, ::mavsdk::rpc::camera::SelectCameraResponse>* streamer) { - return this->StreamedSelectCamera(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_SelectCamera() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SelectCamera(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SelectCameraRequest* /*request*/, ::mavsdk::rpc::camera::SelectCameraResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // 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; - }; - template class WithStreamedUnaryMethod_ResetSettings : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ResetSettings() { - ::grpc::Service::MarkMethodStreamed(21, + ::grpc::Service::MarkMethodStreamed(24, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ResetSettingsRequest, ::mavsdk::rpc::camera::ResetSettingsResponse>( [this](::grpc::ServerContext* context, @@ -5004,7 +5496,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ZoomInStart() { - ::grpc::Service::MarkMethodStreamed(22, + ::grpc::Service::MarkMethodStreamed(25, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>( [this](::grpc::ServerContext* context, @@ -5031,7 +5523,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ZoomOutStart() { - ::grpc::Service::MarkMethodStreamed(23, + ::grpc::Service::MarkMethodStreamed(26, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>( [this](::grpc::ServerContext* context, @@ -5058,7 +5550,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ZoomStop() { - ::grpc::Service::MarkMethodStreamed(24, + ::grpc::Service::MarkMethodStreamed(27, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>( [this](::grpc::ServerContext* context, @@ -5085,7 +5577,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ZoomRange() { - ::grpc::Service::MarkMethodStreamed(25, + ::grpc::Service::MarkMethodStreamed(28, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>( [this](::grpc::ServerContext* context, @@ -5112,7 +5604,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_TrackPoint() { - ::grpc::Service::MarkMethodStreamed(26, + ::grpc::Service::MarkMethodStreamed(29, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>( [this](::grpc::ServerContext* context, @@ -5139,7 +5631,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_TrackRectangle() { - ::grpc::Service::MarkMethodStreamed(27, + ::grpc::Service::MarkMethodStreamed(30, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>( [this](::grpc::ServerContext* context, @@ -5166,7 +5658,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_TrackStop() { - ::grpc::Service::MarkMethodStreamed(28, + ::grpc::Service::MarkMethodStreamed(31, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>( [this](::grpc::ServerContext* context, @@ -5193,7 +5685,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_FocusInStart() { - ::grpc::Service::MarkMethodStreamed(29, + ::grpc::Service::MarkMethodStreamed(32, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>( [this](::grpc::ServerContext* context, @@ -5220,7 +5712,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_FocusOutStart() { - ::grpc::Service::MarkMethodStreamed(30, + ::grpc::Service::MarkMethodStreamed(33, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>( [this](::grpc::ServerContext* context, @@ -5247,7 +5739,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_FocusStop() { - ::grpc::Service::MarkMethodStreamed(31, + ::grpc::Service::MarkMethodStreamed(34, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>( [this](::grpc::ServerContext* context, @@ -5274,7 +5766,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_FocusRange() { - ::grpc::Service::MarkMethodStreamed(32, + ::grpc::Service::MarkMethodStreamed(35, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>( [this](::grpc::ServerContext* context, @@ -5295,60 +5787,60 @@ class CameraService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedFocusRange(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::FocusRangeRequest,::mavsdk::rpc::camera::FocusRangeResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_TakePhoto > > > > > > > > > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; template - class WithSplitStreamingMethod_SubscribeMode : public BaseClass { + class WithSplitStreamingMethod_SubscribeCameraList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithSplitStreamingMethod_SubscribeMode() { - ::grpc::Service::MarkMethodStreamed(10, + WithSplitStreamingMethod_SubscribeCameraList() { + ::grpc::Service::MarkMethodStreamed(9, new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::camera::SubscribeModeRequest, ::mavsdk::rpc::camera::ModeResponse>( + ::mavsdk::rpc::camera::SubscribeCameraListRequest, ::mavsdk::rpc::camera::CameraListResponse>( [this](::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::camera::SubscribeModeRequest, ::mavsdk::rpc::camera::ModeResponse>* streamer) { - return this->StreamedSubscribeMode(context, + ::mavsdk::rpc::camera::SubscribeCameraListRequest, ::mavsdk::rpc::camera::CameraListResponse>* streamer) { + return this->StreamedSubscribeCameraList(context, streamer); })); } - ~WithSplitStreamingMethod_SubscribeMode() override { + ~WithSplitStreamingMethod_SubscribeCameraList() override { BaseClassMustBeDerivedFromService(this); } // disable regular version of this method - ::grpc::Status SubscribeMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::ModeResponse>* /*writer*/) override { + ::grpc::Status SubscribeCameraList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCameraListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CameraListResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeMode(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribeModeRequest,::mavsdk::rpc::camera::ModeResponse>* server_split_streamer) = 0; + virtual ::grpc::Status StreamedSubscribeCameraList(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribeCameraListRequest,::mavsdk::rpc::camera::CameraListResponse>* server_split_streamer) = 0; }; template - class WithSplitStreamingMethod_SubscribeInformation : public BaseClass { + class WithSplitStreamingMethod_SubscribeMode : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithSplitStreamingMethod_SubscribeInformation() { - ::grpc::Service::MarkMethodStreamed(11, + WithSplitStreamingMethod_SubscribeMode() { + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::camera::SubscribeInformationRequest, ::mavsdk::rpc::camera::InformationResponse>( + ::mavsdk::rpc::camera::SubscribeModeRequest, ::mavsdk::rpc::camera::ModeResponse>( [this](::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::camera::SubscribeInformationRequest, ::mavsdk::rpc::camera::InformationResponse>* streamer) { - return this->StreamedSubscribeInformation(context, + ::mavsdk::rpc::camera::SubscribeModeRequest, ::mavsdk::rpc::camera::ModeResponse>* streamer) { + return this->StreamedSubscribeMode(context, streamer); })); } - ~WithSplitStreamingMethod_SubscribeInformation() override { + ~WithSplitStreamingMethod_SubscribeMode() override { BaseClassMustBeDerivedFromService(this); } // disable regular version of this method - ::grpc::Status SubscribeInformation(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeInformationRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::InformationResponse>* /*writer*/) override { + ::grpc::Status SubscribeMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeModeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::ModeResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeInformation(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribeInformationRequest,::mavsdk::rpc::camera::InformationResponse>* server_split_streamer) = 0; + virtual ::grpc::Status StreamedSubscribeMode(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribeModeRequest,::mavsdk::rpc::camera::ModeResponse>* server_split_streamer) = 0; }; template class WithSplitStreamingMethod_SubscribeVideoStreamInfo : public BaseClass { @@ -5383,7 +5875,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeCaptureInfo() { - ::grpc::Service::MarkMethodStreamed(13, + ::grpc::Service::MarkMethodStreamed(14, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeCaptureInfoRequest, ::mavsdk::rpc::camera::CaptureInfoResponse>( [this](::grpc::ServerContext* context, @@ -5410,7 +5902,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStatus() { - ::grpc::Service::MarkMethodStreamed(14, + ::grpc::Service::MarkMethodStreamed(15, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeStatusRequest, ::mavsdk::rpc::camera::StatusResponse>( [this](::grpc::ServerContext* context, @@ -5437,7 +5929,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodStreamed(15, + ::grpc::Service::MarkMethodStreamed(17, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest, ::mavsdk::rpc::camera::CurrentSettingsResponse>( [this](::grpc::ServerContext* context, @@ -5464,7 +5956,7 @@ class CameraService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodStreamed(16, + ::grpc::Service::MarkMethodStreamed(19, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest, ::mavsdk::rpc::camera::PossibleSettingOptionsResponse>( [this](::grpc::ServerContext* context, @@ -5485,8 +5977,8 @@ class CameraService final { // replace default version of method with split streamed 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 WithSplitStreamingMethod_SubscribeCameraList > > > > > > SplitStreamedService; + typedef WithStreamedUnaryMethod_TakePhoto > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > 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 415cd73036..217bde8668 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -23,8 +23,15 @@ namespace _fl = ::google::protobuf::internal::field_layout; namespace mavsdk { namespace rpc { namespace camera { - template -PROTOBUF_CONSTEXPR ZoomStopRequest::ZoomStopRequest(::_pbi::ConstantInitialized) {} + +inline constexpr ZoomStopRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomStopRequest::ZoomStopRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct ZoomStopRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR ZoomStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~ZoomStopRequestDefaultTypeInternal() {} @@ -38,7 +45,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr ZoomRangeRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : range_{0}, + : camera_id_{0}, + range_{0}, _cached_size_{0} {} template @@ -54,8 +62,15 @@ struct ZoomRangeRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomRangeRequestDefaultTypeInternal _ZoomRangeRequest_default_instance_; - template -PROTOBUF_CONSTEXPR ZoomOutStartRequest::ZoomOutStartRequest(::_pbi::ConstantInitialized) {} + +inline constexpr ZoomOutStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomOutStartRequest::ZoomOutStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct ZoomOutStartRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR ZoomOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~ZoomOutStartRequestDefaultTypeInternal() {} @@ -66,8 +81,15 @@ struct ZoomOutStartRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomOutStartRequestDefaultTypeInternal _ZoomOutStartRequest_default_instance_; - template -PROTOBUF_CONSTEXPR ZoomInStartRequest::ZoomInStartRequest(::_pbi::ConstantInitialized) {} + +inline constexpr ZoomInStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomInStartRequest::ZoomInStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct ZoomInStartRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR ZoomInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~ZoomInStartRequestDefaultTypeInternal() {} @@ -105,8 +127,15 @@ struct VideoStreamSettingsDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamSettingsDefaultTypeInternal _VideoStreamSettings_default_instance_; - template -PROTOBUF_CONSTEXPR TrackStopRequest::TrackStopRequest(::_pbi::ConstantInitialized) {} + +inline constexpr TrackStopRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR TrackStopRequest::TrackStopRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct TrackStopRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR TrackStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~TrackStopRequestDefaultTypeInternal() {} @@ -120,7 +149,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr TrackRectangleRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : top_left_x_{0}, + : camera_id_{0}, + top_left_x_{0}, top_left_y_{0}, bottom_right_x_{0}, bottom_right_y_{0}, @@ -142,7 +172,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr TrackPointRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : point_x_{0}, + : camera_id_{0}, + point_x_{0}, point_y_{0}, radius_{0}, _cached_size_{0} {} @@ -160,8 +191,15 @@ struct TrackPointRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackPointRequestDefaultTypeInternal _TrackPointRequest_default_instance_; - template -PROTOBUF_CONSTEXPR TakePhotoRequest::TakePhotoRequest(::_pbi::ConstantInitialized) {} + +inline constexpr TakePhotoRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR TakePhotoRequest::TakePhotoRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct TakePhotoRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR TakePhotoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~TakePhotoRequestDefaultTypeInternal() {} @@ -221,18 +259,6 @@ struct SubscribeModeRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeModeRequestDefaultTypeInternal _SubscribeModeRequest_default_instance_; template -PROTOBUF_CONSTEXPR SubscribeInformationRequest::SubscribeInformationRequest(::_pbi::ConstantInitialized) {} -struct SubscribeInformationRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeInformationRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeInformationRequestDefaultTypeInternal() {} - union { - SubscribeInformationRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeInformationRequestDefaultTypeInternal _SubscribeInformationRequest_default_instance_; - template PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequest::SubscribeCurrentSettingsRequest(::_pbi::ConstantInitialized) {} struct SubscribeCurrentSettingsRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} @@ -256,10 +282,23 @@ struct SubscribeCaptureInfoRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeCaptureInfoRequestDefaultTypeInternal _SubscribeCaptureInfoRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeCameraListRequest::SubscribeCameraListRequest(::_pbi::ConstantInitialized) {} +struct SubscribeCameraListRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeCameraListRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeCameraListRequestDefaultTypeInternal() {} + union { + SubscribeCameraListRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeCameraListRequestDefaultTypeInternal _SubscribeCameraListRequest_default_instance_; inline constexpr StopVideoStreamingRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : stream_id_{0}, + : camera_id_{0}, + stream_id_{0}, _cached_size_{0} {} template @@ -275,8 +314,15 @@ struct StopVideoStreamingRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoStreamingRequestDefaultTypeInternal _StopVideoStreamingRequest_default_instance_; - template -PROTOBUF_CONSTEXPR StopVideoRequest::StopVideoRequest(::_pbi::ConstantInitialized) {} + +inline constexpr StopVideoRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR StopVideoRequest::StopVideoRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct StopVideoRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR StopVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~StopVideoRequestDefaultTypeInternal() {} @@ -287,8 +333,15 @@ struct StopVideoRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StopVideoRequestDefaultTypeInternal _StopVideoRequest_default_instance_; - template -PROTOBUF_CONSTEXPR StopPhotoIntervalRequest::StopPhotoIntervalRequest(::_pbi::ConstantInitialized) {} + +inline constexpr StopPhotoIntervalRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR StopPhotoIntervalRequest::StopPhotoIntervalRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct StopPhotoIntervalRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR StopPhotoIntervalRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~StopPhotoIntervalRequestDefaultTypeInternal() {} @@ -305,6 +358,7 @@ inline constexpr Status::Impl_::Impl_( : media_folder_name_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), + camera_id_{0}, video_on_{false}, photo_interval_on_{false}, used_storage_mib_{0}, @@ -332,7 +386,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr StartVideoStreamingRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : stream_id_{0}, + : camera_id_{0}, + stream_id_{0}, _cached_size_{0} {} template @@ -348,8 +403,15 @@ struct StartVideoStreamingRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 StartVideoStreamingRequestDefaultTypeInternal _StartVideoStreamingRequest_default_instance_; - template -PROTOBUF_CONSTEXPR StartVideoRequest::StartVideoRequest(::_pbi::ConstantInitialized) {} + +inline constexpr StartVideoRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR StartVideoRequest::StartVideoRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct StartVideoRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR StartVideoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~StartVideoRequestDefaultTypeInternal() {} @@ -363,7 +425,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr StartPhotoIntervalRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : interval_s_{0}, + : camera_id_{0}, + interval_s_{0}, _cached_size_{0} {} template @@ -382,7 +445,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr SetModeRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : mode_{static_cast< ::mavsdk::rpc::camera::Mode >(0)}, + : camera_id_{0}, + mode_{static_cast< ::mavsdk::rpc::camera::Mode >(0)}, _cached_size_{0} {} template @@ -399,26 +463,14 @@ struct SetModeRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetModeRequestDefaultTypeInternal _SetModeRequest_default_instance_; -inline constexpr SelectCameraRequest::Impl_::Impl_( +inline constexpr ResetSettingsRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : camera_id_{0}, _cached_size_{0} {} template -PROTOBUF_CONSTEXPR SelectCameraRequest::SelectCameraRequest(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR ResetSettingsRequest::ResetSettingsRequest(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct SelectCameraRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SelectCameraRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SelectCameraRequestDefaultTypeInternal() {} - union { - SelectCameraRequest _instance; - }; -}; - -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() {} @@ -451,18 +503,6 @@ struct QuaternionDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 QuaternionDefaultTypeInternal _Quaternion_default_instance_; - template -PROTOBUF_CONSTEXPR PrepareRequest::PrepareRequest(::_pbi::ConstantInitialized) {} -struct PrepareRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR PrepareRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~PrepareRequestDefaultTypeInternal() {} - union { - PrepareRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PrepareRequestDefaultTypeInternal _PrepareRequest_default_instance_; inline constexpr Position::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -510,28 +550,30 @@ struct OptionDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 OptionDefaultTypeInternal _Option_default_instance_; -inline constexpr ModeResponse::Impl_::Impl_( +inline constexpr ModeInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : mode_{static_cast< ::mavsdk::rpc::camera::Mode >(0)}, + : camera_id_{0}, + mode_{static_cast< ::mavsdk::rpc::camera::Mode >(0)}, _cached_size_{0} {} template -PROTOBUF_CONSTEXPR ModeResponse::ModeResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR ModeInfo::ModeInfo(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct ModeResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR ModeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ModeResponseDefaultTypeInternal() {} +struct ModeInfoDefaultTypeInternal { + PROTOBUF_CONSTEXPR ModeInfoDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ModeInfoDefaultTypeInternal() {} union { - ModeResponse _instance; + ModeInfo _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ModeResponseDefaultTypeInternal _ModeResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ModeInfoDefaultTypeInternal _ModeInfo_default_instance_; inline constexpr ListPhotosRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : photos_range_{static_cast< ::mavsdk::rpc::camera::PhotosRange >(0)}, + : camera_id_{0}, + photos_range_{static_cast< ::mavsdk::rpc::camera::PhotosRange >(0)}, _cached_size_{0} {} template @@ -577,9 +619,124 @@ struct InformationDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 InformationDefaultTypeInternal _Information_default_instance_; +inline constexpr GetVideoStreamInfoRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetVideoStreamInfoRequest::GetVideoStreamInfoRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetVideoStreamInfoRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetVideoStreamInfoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetVideoStreamInfoRequestDefaultTypeInternal() {} + union { + GetVideoStreamInfoRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetVideoStreamInfoRequestDefaultTypeInternal _GetVideoStreamInfoRequest_default_instance_; + +inline constexpr GetStatusRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetStatusRequest::GetStatusRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetStatusRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetStatusRequestDefaultTypeInternal() {} + union { + GetStatusRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetStatusRequestDefaultTypeInternal _GetStatusRequest_default_instance_; + +inline constexpr GetPossibleSettingOptionsRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetPossibleSettingOptionsRequest::GetPossibleSettingOptionsRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetPossibleSettingOptionsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetPossibleSettingOptionsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetPossibleSettingOptionsRequestDefaultTypeInternal() {} + union { + GetPossibleSettingOptionsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetPossibleSettingOptionsRequestDefaultTypeInternal _GetPossibleSettingOptionsRequest_default_instance_; + +inline constexpr GetModeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : mode_{static_cast< ::mavsdk::rpc::camera::Mode >(0)}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetModeResponse::GetModeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetModeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetModeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetModeResponseDefaultTypeInternal() {} + union { + GetModeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetModeResponseDefaultTypeInternal _GetModeResponse_default_instance_; + +inline constexpr GetModeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetModeRequest::GetModeRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetModeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetModeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetModeRequestDefaultTypeInternal() {} + union { + GetModeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetModeRequestDefaultTypeInternal _GetModeRequest_default_instance_; + +inline constexpr GetCurrentSettingsRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetCurrentSettingsRequest::GetCurrentSettingsRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetCurrentSettingsRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetCurrentSettingsRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetCurrentSettingsRequestDefaultTypeInternal() {} + union { + GetCurrentSettingsRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetCurrentSettingsRequestDefaultTypeInternal _GetCurrentSettingsRequest_default_instance_; + inline constexpr FormatStorageRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : storage_id_{0}, + : camera_id_{0}, + storage_id_{0}, _cached_size_{0} {} template @@ -595,8 +752,15 @@ struct FormatStorageRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FormatStorageRequestDefaultTypeInternal _FormatStorageRequest_default_instance_; - template -PROTOBUF_CONSTEXPR FocusStopRequest::FocusStopRequest(::_pbi::ConstantInitialized) {} + +inline constexpr FocusStopRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR FocusStopRequest::FocusStopRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct FocusStopRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR FocusStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~FocusStopRequestDefaultTypeInternal() {} @@ -610,7 +774,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr FocusRangeRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : range_{0}, + : camera_id_{0}, + range_{0}, _cached_size_{0} {} template @@ -626,8 +791,15 @@ struct FocusRangeRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusRangeRequestDefaultTypeInternal _FocusRangeRequest_default_instance_; - template -PROTOBUF_CONSTEXPR FocusOutStartRequest::FocusOutStartRequest(::_pbi::ConstantInitialized) {} + +inline constexpr FocusOutStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR FocusOutStartRequest::FocusOutStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct FocusOutStartRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR FocusOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~FocusOutStartRequestDefaultTypeInternal() {} @@ -638,8 +810,15 @@ struct FocusOutStartRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusOutStartRequestDefaultTypeInternal _FocusOutStartRequest_default_instance_; - template -PROTOBUF_CONSTEXPR FocusInStartRequest::FocusInStartRequest(::_pbi::ConstantInitialized) {} + +inline constexpr FocusInStartRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : camera_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR FocusInStartRequest::FocusInStartRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct FocusInStartRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR FocusInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~FocusInStartRequestDefaultTypeInternal() {} @@ -774,6 +953,7 @@ inline constexpr VideoStreamInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, settings_{nullptr}, + camera_id_{0}, status_{static_cast< ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamStatus >(0)}, spectrum_{static_cast< ::mavsdk::rpc::camera::VideoStreamInfo_VideoStreamSpectrum >(0)} {} @@ -1009,6 +1189,7 @@ inline constexpr SettingOptions::Impl_::Impl_( setting_description_( &::google::protobuf::internal::fixed_address_empty_string, ::_pbi::ConstantInitialized()), + camera_id_{0}, is_range_{false}, _cached_size_{0} {} @@ -1090,25 +1271,6 @@ struct SetModeResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetModeResponseDefaultTypeInternal _SetModeResponse_default_instance_; -inline constexpr SelectCameraResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - camera_result_{nullptr} {} - -template -PROTOBUF_CONSTEXPR SelectCameraResponse::SelectCameraResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct SelectCameraResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR SelectCameraResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SelectCameraResponseDefaultTypeInternal() {} - union { - SelectCameraResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SelectCameraResponseDefaultTypeInternal _SelectCameraResponse_default_instance_; - inline constexpr ResetSettingsResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1128,43 +1290,43 @@ struct ResetSettingsResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; -inline constexpr PrepareResponse::Impl_::Impl_( +inline constexpr ModeResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - camera_result_{nullptr} {} + mode_info_{nullptr} {} template -PROTOBUF_CONSTEXPR PrepareResponse::PrepareResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR ModeResponse::ModeResponse(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct PrepareResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR PrepareResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~PrepareResponseDefaultTypeInternal() {} +struct ModeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ModeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ModeResponseDefaultTypeInternal() {} union { - PrepareResponse _instance; + ModeResponse _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PrepareResponseDefaultTypeInternal _PrepareResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ModeResponseDefaultTypeInternal _ModeResponse_default_instance_; -inline constexpr InformationResponse::Impl_::Impl_( +inline constexpr GetStatusResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - information_{nullptr} {} + status_{nullptr} {} template -PROTOBUF_CONSTEXPR InformationResponse::InformationResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR GetStatusResponse::GetStatusResponse(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct InformationResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR InformationResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~InformationResponseDefaultTypeInternal() {} +struct GetStatusResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetStatusResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetStatusResponseDefaultTypeInternal() {} union { - InformationResponse _instance; + GetStatusResponse _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 InformationResponseDefaultTypeInternal _InformationResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetStatusResponseDefaultTypeInternal _GetStatusResponse_default_instance_; inline constexpr FormatStorageResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -1288,6 +1450,25 @@ struct CaptureInfoDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CaptureInfoDefaultTypeInternal _CaptureInfo_default_instance_; +inline constexpr CameraList::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : cameras_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR CameraList::CameraList(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct CameraListDefaultTypeInternal { + PROTOBUF_CONSTEXPR CameraListDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~CameraListDefaultTypeInternal() {} + union { + CameraList _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraListDefaultTypeInternal _CameraList_default_instance_; + inline constexpr VideoStreamInfoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1310,7 +1491,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr SetSettingRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - setting_{nullptr} {} + setting_{nullptr}, + camera_id_{0} {} template PROTOBUF_CONSTEXPR SetSettingRequest::SetSettingRequest(::_pbi::ConstantInitialized) @@ -1365,6 +1547,25 @@ struct ListPhotosResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ListPhotosResponseDefaultTypeInternal _ListPhotosResponse_default_instance_; +inline constexpr GetVideoStreamInfoResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + video_stream_info_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetVideoStreamInfoResponse::GetVideoStreamInfoResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetVideoStreamInfoResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetVideoStreamInfoResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetVideoStreamInfoResponseDefaultTypeInternal() {} + union { + GetVideoStreamInfoResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetVideoStreamInfoResponseDefaultTypeInternal _GetVideoStreamInfoResponse_default_instance_; + inline constexpr GetSettingResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1388,7 +1589,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr GetSettingRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - setting_{nullptr} {} + setting_{nullptr}, + camera_id_{0} {} template PROTOBUF_CONSTEXPR GetSettingRequest::GetSettingRequest(::_pbi::ConstantInitialized) @@ -1404,15 +1606,55 @@ struct GetSettingRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetSettingRequestDefaultTypeInternal _GetSettingRequest_default_instance_; -inline constexpr CurrentSettingsResponse::Impl_::Impl_( +inline constexpr GetPossibleSettingOptionsResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : current_settings_{}, - _cached_size_{0} {} + : _cached_size_{0}, + setting_options_{}, + camera_result_{nullptr} {} template -PROTOBUF_CONSTEXPR CurrentSettingsResponse::CurrentSettingsResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR GetPossibleSettingOptionsResponse::GetPossibleSettingOptionsResponse(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct CurrentSettingsResponseDefaultTypeInternal { +struct GetPossibleSettingOptionsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetPossibleSettingOptionsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetPossibleSettingOptionsResponseDefaultTypeInternal() {} + union { + GetPossibleSettingOptionsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetPossibleSettingOptionsResponseDefaultTypeInternal _GetPossibleSettingOptionsResponse_default_instance_; + +inline constexpr GetCurrentSettingsResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + current_settings_{}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetCurrentSettingsResponse::GetCurrentSettingsResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetCurrentSettingsResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetCurrentSettingsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetCurrentSettingsResponseDefaultTypeInternal() {} + union { + GetCurrentSettingsResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetCurrentSettingsResponseDefaultTypeInternal _GetCurrentSettingsResponse_default_instance_; + +inline constexpr CurrentSettingsResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : current_settings_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR CurrentSettingsResponse::CurrentSettingsResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct CurrentSettingsResponseDefaultTypeInternal { PROTOBUF_CONSTEXPR CurrentSettingsResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~CurrentSettingsResponseDefaultTypeInternal() {} union { @@ -1441,34 +1683,35 @@ struct CaptureInfoResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CaptureInfoResponseDefaultTypeInternal _CaptureInfoResponse_default_instance_; + +inline constexpr CameraListResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_list_{nullptr} {} + +template +PROTOBUF_CONSTEXPR CameraListResponse::CameraListResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct CameraListResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR CameraListResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~CameraListResponseDefaultTypeInternal() {} + union { + CameraListResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraListResponseDefaultTypeInternal _CameraListResponse_default_instance_; } // namespace camera } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[78]; +static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[86]; 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; const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( protodesc_cold) = { ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::PrepareRequest, _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::PrepareResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::PrepareResponse, _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::PrepareResponse, _impl_.camera_result_), - 0, - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TakePhotoRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1476,6 +1719,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::TakePhotoRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TakePhotoResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TakePhotoResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1494,6 +1738,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::StartPhotoIntervalRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartPhotoIntervalRequest, _impl_.interval_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartPhotoIntervalResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartPhotoIntervalResponse, _internal_metadata_), @@ -1513,6 +1758,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::StopPhotoIntervalRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopPhotoIntervalResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopPhotoIntervalResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1531,6 +1777,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::StartVideoRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1549,6 +1796,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::StopVideoRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1567,6 +1815,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingRequest, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StartVideoStreamingResponse, _internal_metadata_), @@ -1586,6 +1835,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingRequest, _impl_.stream_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::StopVideoStreamingResponse, _internal_metadata_), @@ -1605,6 +1855,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::SetModeRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetModeRequest, _impl_.mode_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetModeResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetModeResponse, _internal_metadata_), @@ -1624,6 +1875,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::ListPhotosRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ListPhotosRequest, _impl_.photos_range_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ListPhotosResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ListPhotosResponse, _internal_metadata_), @@ -1638,32 +1890,42 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION 0, ~0u, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeInformationRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeCameraListRequest, _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::InformationResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::InformationResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraListResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraListResponse, _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::InformationResponse, _impl_.information_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraListResponse, _impl_.camera_list_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeModeRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ModeInfo, _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::ModeInfo, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ModeInfo, _impl_.mode_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeModeRequest, _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::ModeResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ModeResponse, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1671,7 +1933,8 @@ 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::ModeResponse, _impl_.mode_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ModeResponse, _impl_.mode_info_), + 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -1768,7 +2031,9 @@ 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::SetSettingRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetSettingRequest, _impl_.setting_), + ~0u, 0, PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetSettingResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetSettingResponse, _internal_metadata_), @@ -1780,66 +2045,148 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SetSettingResponse, _impl_.camera_result_), 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingRequest, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingRequest, _internal_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetModeRequest, _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::GetSettingRequest, _impl_.setting_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetModeRequest, _impl_.camera_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetModeResponse, _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::GetModeResponse, _impl_.mode_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoRequest, _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::GetVideoStreamInfoRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoResponse, _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::GetVideoStreamInfoResponse, _impl_.video_stream_info_), 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _internal_metadata_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetStatusRequest, _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::GetSettingResponse, _impl_.camera_result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _impl_.setting_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetStatusRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetStatusResponse, _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::GetStatusResponse, _impl_.status_), 0, - 1, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsRequest, _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::FormatStorageRequest, _impl_.storage_id_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsResponse, _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::FormatStorageResponse, _impl_.camera_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsResponse, _impl_.camera_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetCurrentSettingsResponse, _impl_.current_settings_), + 0, + ~0u, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest, _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::GetPossibleSettingOptionsRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, _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::GetPossibleSettingOptionsResponse, _impl_.camera_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse, _impl_.setting_options_), + 0, + ~0u, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingRequest, _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::GetSettingRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingRequest, _impl_.setting_), + ~0u, 0, - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SelectCameraResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SelectCameraResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _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::SelectCameraResponse, _impl_.camera_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _impl_.camera_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetSettingResponse, _impl_.setting_), 0, + 1, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SelectCameraRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageRequest, _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::FormatStorageRequest, _impl_.camera_id_), + 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_ ~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::SelectCameraRequest, _impl_.camera_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FormatStorageResponse, _impl_.camera_result_), + 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsRequest, _internal_metadata_), ~0u, // no _extensions_ @@ -1848,6 +2195,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::ResetSettingsRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1866,6 +2214,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::ZoomInStartRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1884,6 +2233,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::ZoomOutStartRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomOutStartResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomOutStartResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1902,6 +2252,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::ZoomStopRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1920,6 +2271,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::ZoomRangeRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeRequest, _impl_.range_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeResponse, _internal_metadata_), @@ -1939,6 +2291,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::TrackPointRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _impl_.point_x_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _impl_.point_y_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _impl_.radius_), @@ -1960,6 +2313,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::TrackRectangleRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleRequest, _impl_.top_left_x_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleRequest, _impl_.top_left_y_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleRequest, _impl_.bottom_right_x_), @@ -1982,6 +2336,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::TrackStopRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackStopResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackStopResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -2000,6 +2355,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::FocusInStartRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusInStartResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusInStartResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -2018,6 +2374,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::FocusOutStartRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusOutStartResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusOutStartResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -2036,6 +2393,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::FocusStopRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusStopResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusStopResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -2054,6 +2412,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::FocusRangeRequest, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeRequest, _impl_.range_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeResponse, _internal_metadata_), @@ -2155,9 +2514,11 @@ 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::VideoStreamInfo, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.settings_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.status_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::VideoStreamInfo, _impl_.spectrum_), + ~0u, 0, ~0u, ~0u, @@ -2169,6 +2530,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::Status, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Status, _impl_.video_on_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Status, _impl_.photo_interval_on_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Status, _impl_.used_storage_mib_), @@ -2213,6 +2575,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::SettingOptions, _impl_.camera_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SettingOptions, _impl_.setting_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SettingOptions, _impl_.setting_description_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::SettingOptions, _impl_.options_), @@ -2232,93 +2595,108 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.vertical_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.horizontal_resolution_px_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Information, _impl_.vertical_resolution_px_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraList, _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::CameraList, _impl_.cameras_), }; static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - {0, -1, -1, sizeof(::mavsdk::rpc::camera::PrepareRequest)}, - {8, 17, -1, sizeof(::mavsdk::rpc::camera::PrepareResponse)}, - {18, -1, -1, sizeof(::mavsdk::rpc::camera::TakePhotoRequest)}, - {26, 35, -1, sizeof(::mavsdk::rpc::camera::TakePhotoResponse)}, - {36, -1, -1, sizeof(::mavsdk::rpc::camera::StartPhotoIntervalRequest)}, - {45, 54, -1, sizeof(::mavsdk::rpc::camera::StartPhotoIntervalResponse)}, - {55, -1, -1, sizeof(::mavsdk::rpc::camera::StopPhotoIntervalRequest)}, - {63, 72, -1, sizeof(::mavsdk::rpc::camera::StopPhotoIntervalResponse)}, - {73, -1, -1, sizeof(::mavsdk::rpc::camera::StartVideoRequest)}, - {81, 90, -1, sizeof(::mavsdk::rpc::camera::StartVideoResponse)}, - {91, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoRequest)}, - {99, 108, -1, sizeof(::mavsdk::rpc::camera::StopVideoResponse)}, - {109, -1, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingRequest)}, - {118, 127, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingResponse)}, - {128, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingRequest)}, - {137, 146, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingResponse)}, - {147, -1, -1, sizeof(::mavsdk::rpc::camera::SetModeRequest)}, - {156, 165, -1, sizeof(::mavsdk::rpc::camera::SetModeResponse)}, - {166, -1, -1, sizeof(::mavsdk::rpc::camera::ListPhotosRequest)}, - {175, 185, -1, sizeof(::mavsdk::rpc::camera::ListPhotosResponse)}, - {187, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeInformationRequest)}, - {195, 204, -1, sizeof(::mavsdk::rpc::camera::InformationResponse)}, - {205, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeModeRequest)}, - {213, -1, -1, sizeof(::mavsdk::rpc::camera::ModeResponse)}, - {222, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest)}, - {230, 239, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, - {240, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, - {248, 257, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, - {258, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, - {266, 275, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, - {276, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, - {284, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, - {293, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, - {301, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, - {310, 319, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, - {320, 329, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, - {330, 339, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, - {340, 350, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, - {352, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, - {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::ZoomInStartRequest)}, - {416, 425, -1, sizeof(::mavsdk::rpc::camera::ZoomInStartResponse)}, - {426, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomOutStartRequest)}, - {434, 443, -1, sizeof(::mavsdk::rpc::camera::ZoomOutStartResponse)}, - {444, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomStopRequest)}, - {452, 461, -1, sizeof(::mavsdk::rpc::camera::ZoomStopResponse)}, - {462, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomRangeRequest)}, - {471, 480, -1, sizeof(::mavsdk::rpc::camera::ZoomRangeResponse)}, - {481, -1, -1, sizeof(::mavsdk::rpc::camera::TrackPointRequest)}, - {492, 501, -1, sizeof(::mavsdk::rpc::camera::TrackPointResponse)}, - {502, -1, -1, sizeof(::mavsdk::rpc::camera::TrackRectangleRequest)}, - {514, 523, -1, sizeof(::mavsdk::rpc::camera::TrackRectangleResponse)}, - {524, -1, -1, sizeof(::mavsdk::rpc::camera::TrackStopRequest)}, - {532, 541, -1, sizeof(::mavsdk::rpc::camera::TrackStopResponse)}, - {542, -1, -1, sizeof(::mavsdk::rpc::camera::FocusInStartRequest)}, - {550, 559, -1, sizeof(::mavsdk::rpc::camera::FocusInStartResponse)}, - {560, -1, -1, sizeof(::mavsdk::rpc::camera::FocusOutStartRequest)}, - {568, 577, -1, sizeof(::mavsdk::rpc::camera::FocusOutStartResponse)}, - {578, -1, -1, sizeof(::mavsdk::rpc::camera::FocusStopRequest)}, - {586, 595, -1, sizeof(::mavsdk::rpc::camera::FocusStopResponse)}, - {596, -1, -1, sizeof(::mavsdk::rpc::camera::FocusRangeRequest)}, - {605, 614, -1, sizeof(::mavsdk::rpc::camera::FocusRangeResponse)}, - {615, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, - {625, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, - {637, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, - {649, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, - {660, 675, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, - {682, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, - {697, 708, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, - {711, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, - {729, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, - {739, 751, -1, sizeof(::mavsdk::rpc::camera::Setting)}, - {755, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, - {767, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + {0, -1, -1, sizeof(::mavsdk::rpc::camera::TakePhotoRequest)}, + {9, 18, -1, sizeof(::mavsdk::rpc::camera::TakePhotoResponse)}, + {19, -1, -1, sizeof(::mavsdk::rpc::camera::StartPhotoIntervalRequest)}, + {29, 38, -1, sizeof(::mavsdk::rpc::camera::StartPhotoIntervalResponse)}, + {39, -1, -1, sizeof(::mavsdk::rpc::camera::StopPhotoIntervalRequest)}, + {48, 57, -1, sizeof(::mavsdk::rpc::camera::StopPhotoIntervalResponse)}, + {58, -1, -1, sizeof(::mavsdk::rpc::camera::StartVideoRequest)}, + {67, 76, -1, sizeof(::mavsdk::rpc::camera::StartVideoResponse)}, + {77, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoRequest)}, + {86, 95, -1, sizeof(::mavsdk::rpc::camera::StopVideoResponse)}, + {96, -1, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingRequest)}, + {106, 115, -1, sizeof(::mavsdk::rpc::camera::StartVideoStreamingResponse)}, + {116, -1, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingRequest)}, + {126, 135, -1, sizeof(::mavsdk::rpc::camera::StopVideoStreamingResponse)}, + {136, -1, -1, sizeof(::mavsdk::rpc::camera::SetModeRequest)}, + {146, 155, -1, sizeof(::mavsdk::rpc::camera::SetModeResponse)}, + {156, -1, -1, sizeof(::mavsdk::rpc::camera::ListPhotosRequest)}, + {166, 176, -1, sizeof(::mavsdk::rpc::camera::ListPhotosResponse)}, + {178, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCameraListRequest)}, + {186, 195, -1, sizeof(::mavsdk::rpc::camera::CameraListResponse)}, + {196, -1, -1, sizeof(::mavsdk::rpc::camera::ModeInfo)}, + {206, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeModeRequest)}, + {214, 223, -1, sizeof(::mavsdk::rpc::camera::ModeResponse)}, + {224, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeVideoStreamInfoRequest)}, + {232, 241, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfoResponse)}, + {242, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCaptureInfoRequest)}, + {250, 259, -1, sizeof(::mavsdk::rpc::camera::CaptureInfoResponse)}, + {260, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeStatusRequest)}, + {268, 277, -1, sizeof(::mavsdk::rpc::camera::StatusResponse)}, + {278, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest)}, + {286, -1, -1, sizeof(::mavsdk::rpc::camera::CurrentSettingsResponse)}, + {295, -1, -1, sizeof(::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest)}, + {303, -1, -1, sizeof(::mavsdk::rpc::camera::PossibleSettingOptionsResponse)}, + {312, 322, -1, sizeof(::mavsdk::rpc::camera::SetSettingRequest)}, + {324, 333, -1, sizeof(::mavsdk::rpc::camera::SetSettingResponse)}, + {334, -1, -1, sizeof(::mavsdk::rpc::camera::GetModeRequest)}, + {343, -1, -1, sizeof(::mavsdk::rpc::camera::GetModeResponse)}, + {352, -1, -1, sizeof(::mavsdk::rpc::camera::GetVideoStreamInfoRequest)}, + {361, 370, -1, sizeof(::mavsdk::rpc::camera::GetVideoStreamInfoResponse)}, + {371, -1, -1, sizeof(::mavsdk::rpc::camera::GetStatusRequest)}, + {380, 389, -1, sizeof(::mavsdk::rpc::camera::GetStatusResponse)}, + {390, -1, -1, sizeof(::mavsdk::rpc::camera::GetCurrentSettingsRequest)}, + {399, 409, -1, sizeof(::mavsdk::rpc::camera::GetCurrentSettingsResponse)}, + {411, -1, -1, sizeof(::mavsdk::rpc::camera::GetPossibleSettingOptionsRequest)}, + {420, 430, -1, sizeof(::mavsdk::rpc::camera::GetPossibleSettingOptionsResponse)}, + {432, 442, -1, sizeof(::mavsdk::rpc::camera::GetSettingRequest)}, + {444, 454, -1, sizeof(::mavsdk::rpc::camera::GetSettingResponse)}, + {456, -1, -1, sizeof(::mavsdk::rpc::camera::FormatStorageRequest)}, + {466, 475, -1, sizeof(::mavsdk::rpc::camera::FormatStorageResponse)}, + {476, -1, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsRequest)}, + {485, 494, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsResponse)}, + {495, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomInStartRequest)}, + {504, 513, -1, sizeof(::mavsdk::rpc::camera::ZoomInStartResponse)}, + {514, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomOutStartRequest)}, + {523, 532, -1, sizeof(::mavsdk::rpc::camera::ZoomOutStartResponse)}, + {533, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomStopRequest)}, + {542, 551, -1, sizeof(::mavsdk::rpc::camera::ZoomStopResponse)}, + {552, -1, -1, sizeof(::mavsdk::rpc::camera::ZoomRangeRequest)}, + {562, 571, -1, sizeof(::mavsdk::rpc::camera::ZoomRangeResponse)}, + {572, -1, -1, sizeof(::mavsdk::rpc::camera::TrackPointRequest)}, + {584, 593, -1, sizeof(::mavsdk::rpc::camera::TrackPointResponse)}, + {594, -1, -1, sizeof(::mavsdk::rpc::camera::TrackRectangleRequest)}, + {607, 616, -1, sizeof(::mavsdk::rpc::camera::TrackRectangleResponse)}, + {617, -1, -1, sizeof(::mavsdk::rpc::camera::TrackStopRequest)}, + {626, 635, -1, sizeof(::mavsdk::rpc::camera::TrackStopResponse)}, + {636, -1, -1, sizeof(::mavsdk::rpc::camera::FocusInStartRequest)}, + {645, 654, -1, sizeof(::mavsdk::rpc::camera::FocusInStartResponse)}, + {655, -1, -1, sizeof(::mavsdk::rpc::camera::FocusOutStartRequest)}, + {664, 673, -1, sizeof(::mavsdk::rpc::camera::FocusOutStartResponse)}, + {674, -1, -1, sizeof(::mavsdk::rpc::camera::FocusStopRequest)}, + {683, 692, -1, sizeof(::mavsdk::rpc::camera::FocusStopResponse)}, + {693, -1, -1, sizeof(::mavsdk::rpc::camera::FocusRangeRequest)}, + {703, 712, -1, sizeof(::mavsdk::rpc::camera::FocusRangeResponse)}, + {713, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, + {723, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, + {735, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, + {747, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, + {758, 773, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, + {780, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, + {795, 807, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, + {811, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, + {830, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, + {840, 852, -1, sizeof(::mavsdk::rpc::camera::Setting)}, + {856, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, + {869, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + {884, -1, -1, sizeof(::mavsdk::rpc::camera::CameraList)}, }; static const ::_pb::Message* const file_default_instances[] = { - &::mavsdk::rpc::camera::_PrepareRequest_default_instance_._instance, - &::mavsdk::rpc::camera::_PrepareResponse_default_instance_._instance, &::mavsdk::rpc::camera::_TakePhotoRequest_default_instance_._instance, &::mavsdk::rpc::camera::_TakePhotoResponse_default_instance_._instance, &::mavsdk::rpc::camera::_StartPhotoIntervalRequest_default_instance_._instance, @@ -2337,8 +2715,9 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera::_SetModeResponse_default_instance_._instance, &::mavsdk::rpc::camera::_ListPhotosRequest_default_instance_._instance, &::mavsdk::rpc::camera::_ListPhotosResponse_default_instance_._instance, - &::mavsdk::rpc::camera::_SubscribeInformationRequest_default_instance_._instance, - &::mavsdk::rpc::camera::_InformationResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_SubscribeCameraListRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_CameraListResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_ModeInfo_default_instance_._instance, &::mavsdk::rpc::camera::_SubscribeModeRequest_default_instance_._instance, &::mavsdk::rpc::camera::_ModeResponse_default_instance_._instance, &::mavsdk::rpc::camera::_SubscribeVideoStreamInfoRequest_default_instance_._instance, @@ -2353,12 +2732,20 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera::_PossibleSettingOptionsResponse_default_instance_._instance, &::mavsdk::rpc::camera::_SetSettingRequest_default_instance_._instance, &::mavsdk::rpc::camera::_SetSettingResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_GetModeRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_GetModeResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_GetVideoStreamInfoRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_GetVideoStreamInfoResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_GetStatusRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_GetStatusResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_GetCurrentSettingsRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_GetCurrentSettingsResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_GetPossibleSettingOptionsRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_GetPossibleSettingOptionsResponse_default_instance_._instance, &::mavsdk::rpc::camera::_GetSettingRequest_default_instance_._instance, &::mavsdk::rpc::camera::_GetSettingResponse_default_instance_._instance, &::mavsdk::rpc::camera::_FormatStorageRequest_default_instance_._instance, &::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::_ZoomInStartRequest_default_instance_._instance, @@ -2395,265 +2782,305 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::camera::_Setting_default_instance_._instance, &::mavsdk::rpc::camera::_SettingOptions_default_instance_._instance, &::mavsdk::rpc::camera::_Information_default_instance_._instance, + &::mavsdk::rpc::camera::_CameraList_default_instance_._instance, }; const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n\023camera/camera.proto\022\021mavsdk.rpc.camera" - "\032\024mavsdk_options.proto\"\020\n\016PrepareRequest" - "\"I\n\017PrepareResponse\0226\n\rcamera_result\030\001 \001" - "(\0132\037.mavsdk.rpc.camera.CameraResult\"\022\n\020T" - "akePhotoRequest\"K\n\021TakePhotoResponse\0226\n\r" + "\032\024mavsdk_options.proto\"%\n\020TakePhotoReque" + "st\022\021\n\tcamera_id\030\001 \001(\005\"K\n\021TakePhotoRespon" + "se\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.c" + "amera.CameraResult\"B\n\031StartPhotoInterval" + "Request\022\021\n\tcamera_id\030\001 \001(\005\022\022\n\ninterval_s" + "\030\002 \001(\002\"T\n\032StartPhotoIntervalResponse\0226\n\r" "camera_result\030\001 \001(\0132\037.mavsdk.rpc.camera." - "CameraResult\"/\n\031StartPhotoIntervalReques" - "t\022\022\n\ninterval_s\030\001 \001(\002\"T\n\032StartPhotoInter" - "valResponse\0226\n\rcamera_result\030\001 \001(\0132\037.mav" - "sdk.rpc.camera.CameraResult\"\032\n\030StopPhoto" - "IntervalRequest\"S\n\031StopPhotoIntervalResp" - "onse\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc" - ".camera.CameraResult\"\023\n\021StartVideoReques" - "t\"L\n\022StartVideoResponse\0226\n\rcamera_result" - "\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult\"" - "\022\n\020StopVideoRequest\"K\n\021StopVideoResponse" - "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" - "era.CameraResult\"/\n\032StartVideoStreamingR" - "equest\022\021\n\tstream_id\030\001 \001(\005\"U\n\033StartVideoS" - "treamingResponse\0226\n\rcamera_result\030\001 \001(\0132" - "\037.mavsdk.rpc.camera.CameraResult\".\n\031Stop" - "VideoStreamingRequest\022\021\n\tstream_id\030\001 \001(\005" + "CameraResult\"-\n\030StopPhotoIntervalRequest" + "\022\021\n\tcamera_id\030\001 \001(\005\"S\n\031StopPhotoInterval" + "Response\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk" + ".rpc.camera.CameraResult\"&\n\021StartVideoRe" + "quest\022\021\n\tcamera_id\030\001 \001(\005\"L\n\022StartVideoRe" + "sponse\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.r" + "pc.camera.CameraResult\"%\n\020StopVideoReque" + "st\022\021\n\tcamera_id\030\001 \001(\005\"K\n\021StopVideoRespon" + "se\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.c" + "amera.CameraResult\"B\n\032StartVideoStreamin" + "gRequest\022\021\n\tcamera_id\030\001 \001(\005\022\021\n\tstream_id" + "\030\002 \001(\005\"U\n\033StartVideoStreamingResponse\0226\n" + "\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.camera" + ".CameraResult\"A\n\031StopVideoStreamingReque" + "st\022\021\n\tcamera_id\030\001 \001(\005\022\021\n\tstream_id\030\002 \001(\005" "\"T\n\032StopVideoStreamingResponse\0226\n\rcamera" "_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Camera" - "Result\"7\n\016SetModeRequest\022%\n\004mode\030\001 \001(\0162\027" - ".mavsdk.rpc.camera.Mode\"I\n\017SetModeRespon" - "se\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.c" - "amera.CameraResult\"I\n\021ListPhotosRequest\022" - "4\n\014photos_range\030\001 \001(\0162\036.mavsdk.rpc.camer" - "a.PhotosRange\"\203\001\n\022ListPhotosResponse\0226\n\r" - "camera_result\030\001 \001(\0132\037.mavsdk.rpc.camera." - "CameraResult\0225\n\rcapture_infos\030\002 \003(\0132\036.ma" - "vsdk.rpc.camera.CaptureInfo\"\035\n\033Subscribe" - "InformationRequest\"J\n\023InformationRespons" - "e\0223\n\013information\030\001 \001(\0132\036.mavsdk.rpc.came" - "ra.Information\"\026\n\024SubscribeModeRequest\"5" - "\n\014ModeResponse\022%\n\004mode\030\001 \001(\0162\027.mavsdk.rp" - "c.camera.Mode\"!\n\037SubscribeVideoStreamInf" - "oRequest\"X\n\027VideoStreamInfoResponse\022=\n\021v" - "ideo_stream_info\030\001 \001(\0132\".mavsdk.rpc.came" - "ra.VideoStreamInfo\"\035\n\033SubscribeCaptureIn" - "foRequest\"K\n\023CaptureInfoResponse\0224\n\014capt" - "ure_info\030\001 \001(\0132\036.mavsdk.rpc.camera.Captu" - "reInfo\"\030\n\026SubscribeStatusRequest\"B\n\016Stat" - "usResponse\0220\n\rcamera_status\030\001 \001(\0132\031.mavs" - "dk.rpc.camera.Status\"!\n\037SubscribeCurrent" - "SettingsRequest\"O\n\027CurrentSettingsRespon" - "se\0224\n\020current_settings\030\001 \003(\0132\032.mavsdk.rp" - "c.camera.Setting\"(\n&SubscribePossibleSet" - "tingOptionsRequest\"\\\n\036PossibleSettingOpt" - "ionsResponse\022:\n\017setting_options\030\001 \003(\0132!." - "mavsdk.rpc.camera.SettingOptions\"@\n\021SetS" - "ettingRequest\022+\n\007setting\030\001 \001(\0132\032.mavsdk." - "rpc.camera.Setting\"L\n\022SetSettingResponse" - "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" - "era.CameraResult\"@\n\021GetSettingRequest\022+\n" - "\007setting\030\001 \001(\0132\032.mavsdk.rpc.camera.Setti" - "ng\"y\n\022GetSettingResponse\0226\n\rcamera_resul" - "t\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult" - "\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.camera.Se" - "tting\"*\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" + "Result\"J\n\016SetModeRequest\022\021\n\tcamera_id\030\001 " + "\001(\005\022%\n\004mode\030\002 \001(\0162\027.mavsdk.rpc.camera.Mo" + "de\"I\n\017SetModeResponse\0226\n\rcamera_result\030\001" + " \001(\0132\037.mavsdk.rpc.camera.CameraResult\"\\\n" + "\021ListPhotosRequest\022\021\n\tcamera_id\030\001 \001(\005\0224\n" + "\014photos_range\030\002 \001(\0162\036.mavsdk.rpc.camera." + "PhotosRange\"\203\001\n\022ListPhotosResponse\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\"\024\n" - "\022ZoomInStartRequest\"M\n\023ZoomInStartRespon" - "se\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.c" - "amera.CameraResult\"\025\n\023ZoomOutStartReques" - "t\"N\n\024ZoomOutStartResponse\0226\n\rcamera_resu" - "lt\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResul" - "t\"\021\n\017ZoomStopRequest\"J\n\020ZoomStopResponse" - "\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.cam" - "era.CameraResult\"!\n\020ZoomRangeRequest\022\r\n\005" - "range\030\001 \001(\002\"K\n\021ZoomRangeResponse\0226\n\rcame" - "ra_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Came" - "raResult\"E\n\021TrackPointRequest\022\017\n\007point_x" - "\030\001 \001(\002\022\017\n\007point_y\030\002 \001(\002\022\016\n\006radius\030\003 \001(\002\"" - "L\n\022TrackPointResponse\0226\n\rcamera_result\030\001" - " \001(\0132\037.mavsdk.rpc.camera.CameraResult\"o\n" - "\025TrackRectangleRequest\022\022\n\ntop_left_x\030\001 \001" - "(\002\022\022\n\ntop_left_y\030\002 \001(\002\022\026\n\016bottom_right_x" - "\030\003 \001(\002\022\026\n\016bottom_right_y\030\004 \001(\002\"P\n\026TrackR" - "ectangleResponse\0226\n\rcamera_result\030\001 \001(\0132" - "\037.mavsdk.rpc.camera.CameraResult\"\022\n\020Trac" - "kStopRequest\"K\n\021TrackStopResponse\0226\n\rcam" + "meraResult\0225\n\rcapture_infos\030\002 \003(\0132\036.mavs" + "dk.rpc.camera.CaptureInfo\"\034\n\032SubscribeCa" + "meraListRequest\"H\n\022CameraListResponse\0222\n" + "\013camera_list\030\001 \001(\0132\035.mavsdk.rpc.camera.C" + "ameraList\"D\n\010ModeInfo\022\021\n\tcamera_id\030\001 \001(\005" + "\022%\n\004mode\030\002 \001(\0162\027.mavsdk.rpc.camera.Mode\"" + "\026\n\024SubscribeModeRequest\">\n\014ModeResponse\022" + ".\n\tmode_info\030\001 \001(\0132\033.mavsdk.rpc.camera.M" + "odeInfo\"!\n\037SubscribeVideoStreamInfoReque" + "st\"X\n\027VideoStreamInfoResponse\022=\n\021video_s" + "tream_info\030\001 \001(\0132\".mavsdk.rpc.camera.Vid" + "eoStreamInfo\"\035\n\033SubscribeCaptureInfoRequ" + "est\"K\n\023CaptureInfoResponse\0224\n\014capture_in" + "fo\030\001 \001(\0132\036.mavsdk.rpc.camera.CaptureInfo" + "\"\030\n\026SubscribeStatusRequest\"B\n\016StatusResp" + "onse\0220\n\rcamera_status\030\001 \001(\0132\031.mavsdk.rpc" + ".camera.Status\"!\n\037SubscribeCurrentSettin" + "gsRequest\"O\n\027CurrentSettingsResponse\0224\n\020" + "current_settings\030\001 \003(\0132\032.mavsdk.rpc.came" + "ra.Setting\"(\n&SubscribePossibleSettingOp" + "tionsRequest\"\\\n\036PossibleSettingOptionsRe" + "sponse\022:\n\017setting_options\030\001 \003(\0132!.mavsdk" + ".rpc.camera.SettingOptions\"S\n\021SetSetting" + "Request\022\021\n\tcamera_id\030\001 \001(\005\022+\n\007setting\030\002 " + "\001(\0132\032.mavsdk.rpc.camera.Setting\"L\n\022SetSe" + "ttingResponse\0226\n\rcamera_result\030\001 \001(\0132\037.m" + "avsdk.rpc.camera.CameraResult\"#\n\016GetMode" + "Request\022\021\n\tcamera_id\030\001 \001(\005\"8\n\017GetModeRes" + "ponse\022%\n\004mode\030\001 \001(\0162\027.mavsdk.rpc.camera." + "Mode\".\n\031GetVideoStreamInfoRequest\022\021\n\tcam" + "era_id\030\001 \001(\005\"[\n\032GetVideoStreamInfoRespon" + "se\022=\n\021video_stream_info\030\001 \001(\0132\".mavsdk.r" + "pc.camera.VideoStreamInfo\"%\n\020GetStatusRe" + "quest\022\021\n\tcamera_id\030\001 \001(\005\">\n\021GetStatusRes" + "ponse\022)\n\006status\030\001 \001(\0132\031.mavsdk.rpc.camer" + "a.Status\".\n\031GetCurrentSettingsRequest\022\021\n" + "\tcamera_id\030\001 \001(\005\"\212\001\n\032GetCurrentSettingsR" + "esponse\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk." + "rpc.camera.CameraResult\0224\n\020current_setti" + "ngs\030\002 \003(\0132\032.mavsdk.rpc.camera.Setting\"5\n" + " GetPossibleSettingOptionsRequest\022\021\n\tcam" + "era_id\030\001 \001(\005\"\227\001\n!GetPossibleSettingOptio" + "nsResponse\0226\n\rcamera_result\030\001 \001(\0132\037.mavs" + "dk.rpc.camera.CameraResult\022:\n\017setting_op" + "tions\030\002 \003(\0132!.mavsdk.rpc.camera.SettingO" + "ptions\"S\n\021GetSettingRequest\022\021\n\tcamera_id" + "\030\001 \001(\005\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc.cam" + "era.Setting\"y\n\022GetSettingResponse\0226\n\rcam" "era_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Cam" - "eraResult\"\025\n\023FocusInStartRequest\"N\n\024Focu" - "sInStartResponse\0226\n\rcamera_result\030\001 \001(\0132" - "\037.mavsdk.rpc.camera.CameraResult\"\026\n\024Focu" - "sOutStartRequest\"O\n\025FocusOutStartRespons" + "eraResult\022+\n\007setting\030\002 \001(\0132\032.mavsdk.rpc." + "camera.Setting\"=\n\024FormatStorageRequest\022\021" + "\n\tcamera_id\030\001 \001(\005\022\022\n\nstorage_id\030\002 \001(\005\"O\n" + "\025FormatStorageResponse\0226\n\rcamera_result\030" + "\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult\")" + "\n\024ResetSettingsRequest\022\021\n\tcamera_id\030\001 \001(" + "\005\"O\n\025ResetSettingsResponse\0226\n\rcamera_res" + "ult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResu" + "lt\"\'\n\022ZoomInStartRequest\022\021\n\tcamera_id\030\001 " + "\001(\005\"M\n\023ZoomInStartResponse\0226\n\rcamera_res" + "ult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraResu" + "lt\"(\n\023ZoomOutStartRequest\022\021\n\tcamera_id\030\001" + " \001(\005\"N\n\024ZoomOutStartResponse\0226\n\rcamera_r" + "esult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraRe" + "sult\"$\n\017ZoomStopRequest\022\021\n\tcamera_id\030\001 \001" + "(\005\"J\n\020ZoomStopResponse\0226\n\rcamera_result\030" + "\001 \001(\0132\037.mavsdk.rpc.camera.CameraResult\"4" + "\n\020ZoomRangeRequest\022\021\n\tcamera_id\030\001 \001(\005\022\r\n" + "\005range\030\002 \001(\002\"K\n\021ZoomRangeResponse\0226\n\rcam" + "era_result\030\001 \001(\0132\037.mavsdk.rpc.camera.Cam" + "eraResult\"X\n\021TrackPointRequest\022\021\n\tcamera" + "_id\030\001 \001(\005\022\017\n\007point_x\030\002 \001(\002\022\017\n\007point_y\030\003 " + "\001(\002\022\016\n\006radius\030\004 \001(\002\"L\n\022TrackPointRespons" "e\0226\n\rcamera_result\030\001 \001(\0132\037.mavsdk.rpc.ca" - "mera.CameraResult\"\022\n\020FocusStopRequest\"K\n" - "\021FocusStopResponse\0226\n\rcamera_result\030\001 \001(" - "\0132\037.mavsdk.rpc.camera.CameraResult\"\"\n\021Fo" - "cusRangeRequest\022\r\n\005range\030\001 \001(\002\"L\n\022FocusR" - "angeResponse\0226\n\rcamera_result\030\001 \001(\0132\037.ma" - "vsdk.rpc.camera.CameraResult\"\301\002\n\014CameraR" - "esult\0226\n\006result\030\001 \001(\0162&.mavsdk.rpc.camer" - "a.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\016RESU" - "LT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGRESS\020\002\022\017\n\013" - "RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020\004\022\020\n\014RESU" - "LT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025RESULT" - "_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYSTEM\020\010\022" - "\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020\t\"q\n\010Posi" - "tion\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\023relative_altitude_m\030\004 \001(\002\"8\n\nQuaternio" - "n\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\013Ca" - "ptureInfo\022-\n\010position\030\001 \001(\0132\033.mavsdk.rpc" - ".camera.Position\022:\n\023attitude_quaternion\030" - "\002 \001(\0132\035.mavsdk.rpc.camera.Quaternion\022;\n\024" - "attitude_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\010fil" - "e_url\030\007 \001(\t\"\305\001\n\023VideoStreamSettings\022\025\n\rf" - "rame_rate_hz\030\001 \001(\002\022!\n\031horizontal_resolut" - "ion_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\014rotation" - "_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022horizontal_fo" - "v_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo\0228\n\010setti" - "ngs\030\001 \001(\0132&.mavsdk.rpc.camera.VideoStrea" - "mSettings\022D\n\006status\030\002 \001(\01624.mavsdk.rpc.c" - "amera.VideoStreamInfo.VideoStreamStatus\022" - "H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc.camera.Vi" - "deoStreamInfo.VideoStreamSpectrum\"]\n\021Vid" - "eoStreamStatus\022#\n\037VIDEO_STREAM_STATUS_NO" - "T_RUNNING\020\000\022#\n\037VIDEO_STREAM_STATUS_IN_PR" - "OGRESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!\n\035VIDE" - "O_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VIDEO_STR" - "EAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VIDEO_ST" - "REAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006Status\022\020\n\010v" - "ideo_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\025available_" - "storage_mib\030\004 \001(\002\022\031\n\021total_storage_mib\030\005" - " \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022\031\n\021media_" - "folder_name\030\007 \001(\t\022\?\n\016storage_status\030\010 \001(" - "\0162\'.mavsdk.rpc.camera.Status.StorageStat" - "us\022\022\n\nstorage_id\030\t \001(\r\022;\n\014storage_type\030\n" - " \001(\0162%.mavsdk.rpc.camera.Status.StorageT" - "ype\"\221\001\n\rStorageStatus\022 \n\034STORAGE_STATUS_" - "NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STATUS_UNFORM" - "ATTED\020\001\022\034\n\030STORAGE_STATUS_FORMATTED\020\002\022 \n" - "\034STORAGE_STATUS_NOT_SUPPORTED\020\003\"\240\001\n\013Stor" - "ageType\022\030\n\024STORAGE_TYPE_UNKNOWN\020\000\022\032\n\026STO" - "RAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAGE_TYPE_SD" - "\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n\017STORAGE_" - "TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER\020\376\001\"7\n\006Op" - "tion\022\021\n\toption_id\030\001 \001(\t\022\032\n\022option_descri" - "ption\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\006optio" - "n\030\003 \001(\0132\031.mavsdk.rpc.camera.Option\022\020\n\010is" - "_range\030\004 \001(\010\"\177\n\016SettingOptions\022\022\n\nsettin" - "g_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.Opt" - "ion\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Information\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\031horizontal_se" - "nsor_size_mm\030\004 \001(\002\022\037\n\027vertical_sensor_si" - "ze_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_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_SINCE_CONNE" - "CTION\020\0012\315\032\n\rCameraService\022R\n\007Prepare\022!.m" - "avsdk.rpc.camera.PrepareRequest\032\".mavsdk" - ".rpc.camera.PrepareResponse\"\000\022X\n\tTakePho" - "to\022#.mavsdk.rpc.camera.TakePhotoRequest\032" - "$.mavsdk.rpc.camera.TakePhotoResponse\"\000\022" - "s\n\022StartPhotoInterval\022,.mavsdk.rpc.camer" - "a.StartPhotoIntervalRequest\032-.mavsdk.rpc" - ".camera.StartPhotoIntervalResponse\"\000\022p\n\021" - "StopPhotoInterval\022+.mavsdk.rpc.camera.St" - "opPhotoIntervalRequest\032,.mavsdk.rpc.came" - "ra.StopPhotoIntervalResponse\"\000\022[\n\nStartV" - "ideo\022$.mavsdk.rpc.camera.StartVideoReque" - "st\032%.mavsdk.rpc.camera.StartVideoRespons" - "e\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.camera.Sto" - "pVideoRequest\032$.mavsdk.rpc.camera.StopVi" - "deoResponse\"\000\022z\n\023StartVideoStreaming\022-.m" - "avsdk.rpc.camera.StartVideoStreamingRequ" - "est\032..mavsdk.rpc.camera.StartVideoStream" - "ingResponse\"\004\200\265\030\001\022w\n\022StopVideoStreaming\022" - ",.mavsdk.rpc.camera.StopVideoStreamingRe" - "quest\032-.mavsdk.rpc.camera.StopVideoStrea" - "mingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!.mavsdk.r" - "pc.camera.SetModeRequest\032\".mavsdk.rpc.ca" - "mera.SetModeResponse\"\000\022[\n\nListPhotos\022$.m" - "avsdk.rpc.camera.ListPhotosRequest\032%.mav" - "sdk.rpc.camera.ListPhotosResponse\"\000\022]\n\rS" - "ubscribeMode\022\'.mavsdk.rpc.camera.Subscri" - "beModeRequest\032\037.mavsdk.rpc.camera.ModeRe" - "sponse\"\0000\001\022r\n\024SubscribeInformation\022..mav" - "sdk.rpc.camera.SubscribeInformationReque" - "st\032&.mavsdk.rpc.camera.InformationRespon" - "se\"\0000\001\022~\n\030SubscribeVideoStreamInfo\0222.mav" - "sdk.rpc.camera.SubscribeVideoStreamInfoR" - "equest\032*.mavsdk.rpc.camera.VideoStreamIn" - "foResponse\"\0000\001\022v\n\024SubscribeCaptureInfo\022." - ".mavsdk.rpc.camera.SubscribeCaptureInfoR" - "equest\032&.mavsdk.rpc.camera.CaptureInfoRe" - "sponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStatus\022).mavs" - "dk.rpc.camera.SubscribeStatusRequest\032!.m" - "avsdk.rpc.camera.StatusResponse\"\0000\001\022\202\001\n\030" - "SubscribeCurrentSettings\0222.mavsdk.rpc.ca" - "mera.SubscribeCurrentSettingsRequest\032*.m" - "avsdk.rpc.camera.CurrentSettingsResponse" - "\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleSettingOpt" - "ions\0229.mavsdk.rpc.camera.SubscribePossib" - "leSettingOptionsRequest\0321.mavsdk.rpc.cam" - "era.PossibleSettingOptionsResponse\"\0000\001\022[" - "\n\nSetSetting\022$.mavsdk.rpc.camera.SetSett" - "ingRequest\032%.mavsdk.rpc.camera.SetSettin" - "gResponse\"\000\022[\n\nGetSetting\022$.mavsdk.rpc.c" - "amera.GetSettingRequest\032%.mavsdk.rpc.cam" - "era.GetSettingResponse\"\000\022d\n\rFormatStorag" - "e\022\'.mavsdk.rpc.camera.FormatStorageReque" - "st\032(.mavsdk.rpc.camera.FormatStorageResp" - "onse\"\000\022e\n\014SelectCamera\022&.mavsdk.rpc.came" - "ra.SelectCameraRequest\032\'.mavsdk.rpc.came" - "ra.SelectCameraResponse\"\004\200\265\030\001\022d\n\rResetSe" - "ttings\022\'.mavsdk.rpc.camera.ResetSettings" - "Request\032(.mavsdk.rpc.camera.ResetSetting" - "sResponse\"\000\022^\n\013ZoomInStart\022%.mavsdk.rpc." - "camera.ZoomInStartRequest\032&.mavsdk.rpc.c" - "amera.ZoomInStartResponse\"\000\022a\n\014ZoomOutSt" - "art\022&.mavsdk.rpc.camera.ZoomOutStartRequ" - "est\032\'.mavsdk.rpc.camera.ZoomOutStartResp" - "onse\"\000\022U\n\010ZoomStop\022\".mavsdk.rpc.camera.Z" - "oomStopRequest\032#.mavsdk.rpc.camera.ZoomS" - "topResponse\"\000\022X\n\tZoomRange\022#.mavsdk.rpc." - "camera.ZoomRangeRequest\032$.mavsdk.rpc.cam" - "era.ZoomRangeResponse\"\000\022[\n\nTrackPoint\022$." - "mavsdk.rpc.camera.TrackPointRequest\032%.ma" - "vsdk.rpc.camera.TrackPointResponse\"\000\022g\n\016" - "TrackRectangle\022(.mavsdk.rpc.camera.Track" - "RectangleRequest\032).mavsdk.rpc.camera.Tra" - "ckRectangleResponse\"\000\022X\n\tTrackStop\022#.mav" - "sdk.rpc.camera.TrackStopRequest\032$.mavsdk" - ".rpc.camera.TrackStopResponse\"\000\022a\n\014Focus" - "InStart\022&.mavsdk.rpc.camera.FocusInStart" - "Request\032\'.mavsdk.rpc.camera.FocusInStart" - "Response\"\000\022d\n\rFocusOutStart\022\'.mavsdk.rpc" - ".camera.FocusOutStartRequest\032(.mavsdk.rp" - "c.camera.FocusOutStartResponse\"\000\022X\n\tFocu" - "sStop\022#.mavsdk.rpc.camera.FocusStopReque" - "st\032$.mavsdk.rpc.camera.FocusStopResponse" - "\"\000\022[\n\nFocusRange\022$.mavsdk.rpc.camera.Foc" - "usRangeRequest\032%.mavsdk.rpc.camera.Focus" - "RangeResponse\"\000B\037\n\020io.mavsdk.cameraB\013Cam" - "eraProtob\006proto3" + "mera.CameraResult\"\202\001\n\025TrackRectangleRequ" + "est\022\021\n\tcamera_id\030\001 \001(\005\022\022\n\ntop_left_x\030\002 \001" + "(\002\022\022\n\ntop_left_y\030\003 \001(\002\022\026\n\016bottom_right_x" + "\030\004 \001(\002\022\026\n\016bottom_right_y\030\005 \001(\002\"P\n\026TrackR" + "ectangleResponse\0226\n\rcamera_result\030\001 \001(\0132" + "\037.mavsdk.rpc.camera.CameraResult\"%\n\020Trac" + "kStopRequest\022\021\n\tcamera_id\030\001 \001(\005\"K\n\021Track" + "StopResponse\0226\n\rcamera_result\030\001 \001(\0132\037.ma" + "vsdk.rpc.camera.CameraResult\"(\n\023FocusInS" + "tartRequest\022\021\n\tcamera_id\030\001 \001(\005\"N\n\024FocusI" + "nStartResponse\0226\n\rcamera_result\030\001 \001(\0132\037." + "mavsdk.rpc.camera.CameraResult\")\n\024FocusO" + "utStartRequest\022\021\n\tcamera_id\030\001 \001(\005\"O\n\025Foc" + "usOutStartResponse\0226\n\rcamera_result\030\001 \001(" + "\0132\037.mavsdk.rpc.camera.CameraResult\"%\n\020Fo" + "cusStopRequest\022\021\n\tcamera_id\030\001 \001(\005\"K\n\021Foc" + "usStopResponse\0226\n\rcamera_result\030\001 \001(\0132\037." + "mavsdk.rpc.camera.CameraResult\"5\n\021FocusR" + "angeRequest\022\021\n\tcamera_id\030\001 \001(\005\022\r\n\005range\030" + "\002 \001(\002\"L\n\022FocusRangeResponse\0226\n\rcamera_re" + "sult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraRes" + "ult\"\301\002\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.m" + "avsdk.rpc.camera.CameraResult.Result\022\022\n\n" + "result_str\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UN" + "KNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN" + "_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_D" + "ENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIME" + "OUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESU" + "LT_NO_SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPP" + "ORTED\020\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(" + "\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_alt" + "itude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004 \001" + "(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t" + "\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010ro" + "ll_deg\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_d" + "eg\030\003 \001(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001" + "(\0132\033.mavsdk.rpc.camera.Position\022:\n\023attit" + "ude_quaternion\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\005ind" + "ex\030\006 \001(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStre" + "amSettings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031hor" + "izontal_resolution_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\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032" + "\n\022horizontal_fov_deg\030\007 \001(\002\"\325\003\n\017VideoStre" + "amInfo\022\021\n\tcamera_id\030\001 \001(\005\0228\n\010settings\030\002 " + "\001(\0132&.mavsdk.rpc.camera.VideoStreamSetti" + "ngs\022D\n\006status\030\003 \001(\01624.mavsdk.rpc.camera." + "VideoStreamInfo.VideoStreamStatus\022H\n\010spe" + "ctrum\030\004 \001(\01626.mavsdk.rpc.camera.VideoStr" + "eamInfo.VideoStreamSpectrum\"]\n\021VideoStre" + "amStatus\022#\n\037VIDEO_STREAM_STATUS_NOT_RUNN" + "ING\020\000\022#\n\037VIDEO_STREAM_STATUS_IN_PROGRESS" + "\020\001\"\205\001\n\023VideoStreamSpectrum\022!\n\035VIDEO_STRE" + "AM_SPECTRUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM_SP" + "ECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREAM_S" + "PECTRUM_INFRARED\020\002\"\232\005\n\006Status\022\021\n\tcamera_" + "id\030\001 \001(\005\022\020\n\010video_on\030\002 \001(\010\022\031\n\021photo_inte" + "rval_on\030\003 \001(\010\022\030\n\020used_storage_mib\030\004 \001(\002\022" + "\035\n\025available_storage_mib\030\005 \001(\002\022\031\n\021total_" + "storage_mib\030\006 \001(\002\022\030\n\020recording_time_s\030\007 " + "\001(\002\022\031\n\021media_folder_name\030\010 \001(\t\022\?\n\016storag" + "e_status\030\t \001(\0162\'.mavsdk.rpc.camera.Statu" + "s.StorageStatus\022\022\n\nstorage_id\030\n \001(\r\022;\n\014s" + "torage_type\030\013 \001(\0162%.mavsdk.rpc.camera.St" + "atus.StorageType\"\221\001\n\rStorageStatus\022 \n\034ST" + "ORAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_" + "STATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_F" + "ORMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORT" + "ED\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNK" + "NOWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017ST" + "ORAGE_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_O" + "THER\020\376\001\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022" + "option_description\030\002 \001(\t\"w\n\007Setting\022\022\n\ns" + "etting_id\030\001 \001(\t\022\033\n\023setting_description\030\002" + " \001(\t\022)\n\006option\030\003 \001(\0132\031.mavsdk.rpc.camera" + ".Option\022\020\n\010is_range\030\004 \001(\010\"\222\001\n\016SettingOpt" + "ions\022\021\n\tcamera_id\030\001 \001(\005\022\022\n\nsetting_id\030\002 " + "\001(\t\022\033\n\023setting_description\030\003 \001(\t\022*\n\007opti" + "ons\030\004 \003(\0132\031.mavsdk.rpc.camera.Option\022\020\n\010" + "is_range\030\005 \001(\010\"\325\001\n\013Information\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\031horizontal_sensor_si" + "ze_mm\030\004 \001(\002\022\037\n\027vertical_sensor_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\"=\n\nCamera" + "List\022/\n\007cameras\030\001 \003(\0132\036.mavsdk.rpc.camer" + "a.Information*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\013Photo" + "sRange\022\024\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_R" + "ANGE_SINCE_CONNECTION\020\0012\327\035\n\rCameraServic" + "e\022X\n\tTakePhoto\022#.mavsdk.rpc.camera.TakeP" + "hotoRequest\032$.mavsdk.rpc.camera.TakePhot" + "oResponse\"\000\022s\n\022StartPhotoInterval\022,.mavs" + "dk.rpc.camera.StartPhotoIntervalRequest\032" + "-.mavsdk.rpc.camera.StartPhotoIntervalRe" + "sponse\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.r" + "pc.camera.StopPhotoIntervalRequest\032,.mav" + "sdk.rpc.camera.StopPhotoIntervalResponse" + "\"\000\022[\n\nStartVideo\022$.mavsdk.rpc.camera.Sta" + "rtVideoRequest\032%.mavsdk.rpc.camera.Start" + "VideoResponse\"\000\022X\n\tStopVideo\022#.mavsdk.rp" + "c.camera.StopVideoRequest\032$.mavsdk.rpc.c" + "amera.StopVideoResponse\"\000\022z\n\023StartVideoS" + "treaming\022-.mavsdk.rpc.camera.StartVideoS" + "treamingRequest\032..mavsdk.rpc.camera.Star" + "tVideoStreamingResponse\"\004\200\265\030\001\022w\n\022StopVid" + "eoStreaming\022,.mavsdk.rpc.camera.StopVide" + "oStreamingRequest\032-.mavsdk.rpc.camera.St" + "opVideoStreamingResponse\"\004\200\265\030\001\022R\n\007SetMod" + "e\022!.mavsdk.rpc.camera.SetModeRequest\032\".m" + "avsdk.rpc.camera.SetModeResponse\"\000\022[\n\nLi" + "stPhotos\022$.mavsdk.rpc.camera.ListPhotosR" + "equest\032%.mavsdk.rpc.camera.ListPhotosRes" + "ponse\"\000\022o\n\023SubscribeCameraList\022-.mavsdk." + "rpc.camera.SubscribeCameraListRequest\032%." + "mavsdk.rpc.camera.CameraListResponse\"\0000\001" + "\022a\n\rSubscribeMode\022\'.mavsdk.rpc.camera.Su" + "bscribeModeRequest\032\037.mavsdk.rpc.camera.M" + "odeResponse\"\004\200\265\030\0000\001\022V\n\007GetMode\022!.mavsdk." + "rpc.camera.GetModeRequest\032\".mavsdk.rpc.c" + "amera.GetModeResponse\"\004\200\265\030\001\022\202\001\n\030Subscrib" + "eVideoStreamInfo\0222.mavsdk.rpc.camera.Sub" + "scribeVideoStreamInfoRequest\032*.mavsdk.rp" + "c.camera.VideoStreamInfoResponse\"\004\200\265\030\0000\001" + "\022w\n\022GetVideoStreamInfo\022,.mavsdk.rpc.came" + "ra.GetVideoStreamInfoRequest\032-.mavsdk.rp" + "c.camera.GetVideoStreamInfoResponse\"\004\200\265\030" + "\001\022v\n\024SubscribeCaptureInfo\022..mavsdk.rpc.c" + "amera.SubscribeCaptureInfoRequest\032&.mavs" + "dk.rpc.camera.CaptureInfoResponse\"\004\200\265\030\0000" + "\001\022g\n\017SubscribeStatus\022).mavsdk.rpc.camera" + ".SubscribeStatusRequest\032!.mavsdk.rpc.cam" + "era.StatusResponse\"\004\200\265\030\0000\001\022\\\n\tGetStatus\022" + "#.mavsdk.rpc.camera.GetStatusRequest\032$.m" + "avsdk.rpc.camera.GetStatusResponse\"\004\200\265\030\001" + "\022\202\001\n\030SubscribeCurrentSettings\0222.mavsdk.r" + "pc.camera.SubscribeCurrentSettingsReques" + "t\032*.mavsdk.rpc.camera.CurrentSettingsRes" + "ponse\"\004\200\265\030\0000\001\022w\n\022GetCurrentSettings\022,.ma" + "vsdk.rpc.camera.GetCurrentSettingsReques" + "t\032-.mavsdk.rpc.camera.GetCurrentSettings" + "Response\"\004\200\265\030\001\022\227\001\n\037SubscribePossibleSett" + "ingOptions\0229.mavsdk.rpc.camera.Subscribe" + "PossibleSettingOptionsRequest\0321.mavsdk.r" + "pc.camera.PossibleSettingOptionsResponse" + "\"\004\200\265\030\0000\001\022\214\001\n\031GetPossibleSettingOptions\0223" + ".mavsdk.rpc.camera.GetPossibleSettingOpt" + "ionsRequest\0324.mavsdk.rpc.camera.GetPossi" + "bleSettingOptionsResponse\"\004\200\265\030\001\022[\n\nSetSe" + "tting\022$.mavsdk.rpc.camera.SetSettingRequ" + "est\032%.mavsdk.rpc.camera.SetSettingRespon" + "se\"\000\022[\n\nGetSetting\022$.mavsdk.rpc.camera.G" + "etSettingRequest\032%.mavsdk.rpc.camera.Get" + "SettingResponse\"\000\022d\n\rFormatStorage\022\'.mav" + "sdk.rpc.camera.FormatStorageRequest\032(.ma" + "vsdk.rpc.camera.FormatStorageResponse\"\000\022" + "d\n\rResetSettings\022\'.mavsdk.rpc.camera.Res" + "etSettingsRequest\032(.mavsdk.rpc.camera.Re" + "setSettingsResponse\"\000\022^\n\013ZoomInStart\022%.m" + "avsdk.rpc.camera.ZoomInStartRequest\032&.ma" + "vsdk.rpc.camera.ZoomInStartResponse\"\000\022a\n" + "\014ZoomOutStart\022&.mavsdk.rpc.camera.ZoomOu" + "tStartRequest\032\'.mavsdk.rpc.camera.ZoomOu" + "tStartResponse\"\000\022U\n\010ZoomStop\022\".mavsdk.rp" + "c.camera.ZoomStopRequest\032#.mavsdk.rpc.ca" + "mera.ZoomStopResponse\"\000\022X\n\tZoomRange\022#.m" + "avsdk.rpc.camera.ZoomRangeRequest\032$.mavs" + "dk.rpc.camera.ZoomRangeResponse\"\000\022[\n\nTra" + "ckPoint\022$.mavsdk.rpc.camera.TrackPointRe" + "quest\032%.mavsdk.rpc.camera.TrackPointResp" + "onse\"\000\022g\n\016TrackRectangle\022(.mavsdk.rpc.ca" + "mera.TrackRectangleRequest\032).mavsdk.rpc." + "camera.TrackRectangleResponse\"\000\022X\n\tTrack" + "Stop\022#.mavsdk.rpc.camera.TrackStopReques" + "t\032$.mavsdk.rpc.camera.TrackStopResponse\"" + "\000\022a\n\014FocusInStart\022&.mavsdk.rpc.camera.Fo" + "cusInStartRequest\032\'.mavsdk.rpc.camera.Fo" + "cusInStartResponse\"\000\022d\n\rFocusOutStart\022\'." + "mavsdk.rpc.camera.FocusOutStartRequest\032(" + ".mavsdk.rpc.camera.FocusOutStartResponse" + "\"\000\022X\n\tFocusStop\022#.mavsdk.rpc.camera.Focu" + "sStopRequest\032$.mavsdk.rpc.camera.FocusSt" + "opResponse\"\000\022[\n\nFocusRange\022$.mavsdk.rpc." + "camera.FocusRangeRequest\032%.mavsdk.rpc.ca" + "mera.FocusRangeResponse\"\000B\037\n\020io.mavsdk.c" + "ameraB\013CameraProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -2663,13 +3090,13 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 10256, + 11826, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, descriptor_table_camera_2fcamera_2eproto_deps, 1, - 78, + 86, schemas, file_default_instances, TableStruct_camera_2fcamera_2eproto::offsets, @@ -2833,119 +3260,51 @@ bool PhotosRange_IsValid(int value) { } // =================================================================== -class PrepareRequest::_Internal { - public: -}; - -PrepareRequest::PrepareRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.PrepareRequest) -} -PrepareRequest::PrepareRequest( - ::google::protobuf::Arena* arena, - const PrepareRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - PrepareRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.PrepareRequest) -} - - - - - - - - - -::google::protobuf::Metadata PrepareRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[0]); -} -// =================================================================== - -class PrepareResponse::_Internal { +class TakePhotoRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PrepareResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const PrepareResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::CameraResult& PrepareResponse::_Internal::camera_result(const PrepareResponse* msg) { - return *msg->_impl_.camera_result_; -} -PrepareResponse::PrepareResponse(::google::protobuf::Arena* arena) +TakePhotoRequest::TakePhotoRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.PrepareResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TakePhotoRequest) } -inline PROTOBUF_NDEBUG_INLINE PrepareResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -PrepareResponse::PrepareResponse( - ::google::protobuf::Arena* arena, - const PrepareResponse& from) - : ::google::protobuf::Message(arena) { - PrepareResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.PrepareResponse) +TakePhotoRequest::TakePhotoRequest( + ::google::protobuf::Arena* arena, const TakePhotoRequest& from) + : TakePhotoRequest(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE PrepareResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TakePhotoRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PrepareResponse::SharedCtor(::_pb::Arena* arena) { +inline void TakePhotoRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + _impl_.camera_id_ = {}; } -PrepareResponse::~PrepareResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.PrepareResponse) +TakePhotoRequest::~TakePhotoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TakePhotoRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void PrepareResponse::SharedDtor() { +inline void TakePhotoRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void PrepareResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.PrepareResponse) +PROTOBUF_NOINLINE void TakePhotoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TakePhotoRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - 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(); + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* PrepareResponse::_InternalParse( +const char* TakePhotoRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -2953,160 +3312,121 @@ const char* PrepareResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PrepareResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> TakePhotoRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(PrepareResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_PrepareResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_TakePhotoRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PrepareResponse, _impl_.camera_result_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TakePhotoRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(TakePhotoRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(PrepareResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, - }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(TakePhotoRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* PrepareResponse::_InternalSerialize( +::uint8_t* TakePhotoRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.PrepareResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TakePhotoRequest) ::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 = ::google::protobuf::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 = + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.PrepareResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TakePhotoRequest) return target; } -::size_t PrepareResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.PrepareResponse) +::size_t TakePhotoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TakePhotoRequest) ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData PrepareResponse::_class_data_ = { - PrepareResponse::MergeImpl, +const ::google::protobuf::Message::ClassData TakePhotoRequest::_class_data_ = { + TakePhotoRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* PrepareResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* TakePhotoRequest::GetClassData() const { return &_class_data_; } -void PrepareResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.PrepareResponse) +void TakePhotoRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TakePhotoRequest) 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()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PrepareResponse::CopyFrom(const PrepareResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.PrepareResponse) +void TakePhotoRequest::CopyFrom(const TakePhotoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TakePhotoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool PrepareResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool TakePhotoRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* PrepareResponse::AccessCachedSize() const { +::_pbi::CachedSize* TakePhotoRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void PrepareResponse::InternalSwap(PrepareResponse* PROTOBUF_RESTRICT other) { +void TakePhotoRequest::InternalSwap(TakePhotoRequest* PROTOBUF_RESTRICT 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_); -} - -::google::protobuf::Metadata PrepareResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[1]); -} -// =================================================================== - -class TakePhotoRequest::_Internal { - public: -}; - -TakePhotoRequest::TakePhotoRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TakePhotoRequest) -} -TakePhotoRequest::TakePhotoRequest( - ::google::protobuf::Arena* arena, - const TakePhotoRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - TakePhotoRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TakePhotoRequest) + swap(_impl_.camera_id_, other->_impl_.camera_id_); } - - - - - - - - ::google::protobuf::Metadata TakePhotoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[2]); + file_level_metadata_camera_2fcamera_2eproto[0]); } // =================================================================== @@ -3313,7 +3633,7 @@ void TakePhotoResponse::InternalSwap(TakePhotoResponse* PROTOBUF_RESTRICT other) ::google::protobuf::Metadata TakePhotoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[3]); + file_level_metadata_camera_2fcamera_2eproto[1]); } // =================================================================== @@ -3338,7 +3658,12 @@ inline PROTOBUF_NDEBUG_INLINE StartPhotoIntervalRequest::Impl_::Impl_( inline void StartPhotoIntervalRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.interval_s_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, interval_s_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::interval_s_)); } StartPhotoIntervalRequest::~StartPhotoIntervalRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StartPhotoIntervalRequest) @@ -3357,7 +3682,9 @@ PROTOBUF_NOINLINE void StartPhotoIntervalRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.interval_s_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.interval_s_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.interval_s_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -3369,27 +3696,33 @@ const char* StartPhotoIntervalRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StartPhotoIntervalRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> StartPhotoIntervalRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_StartPhotoIntervalRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // float interval_s = 1; + // float interval_s = 2; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.interval_s_)}}, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.interval_s_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StartPhotoIntervalRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // float interval_s = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float interval_s = 2; {PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.interval_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, @@ -3405,7 +3738,14 @@ ::uint8_t* StartPhotoIntervalRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float interval_s = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // float interval_s = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_interval_s = this->_internal_interval_s(); @@ -3414,7 +3754,7 @@ ::uint8_t* StartPhotoIntervalRequest::_InternalSerialize( if (raw_interval_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_interval_s(), target); + 2, this->_internal_interval_s(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -3434,7 +3774,13 @@ ::size_t StartPhotoIntervalRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float interval_s = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // float interval_s = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_interval_s = this->_internal_interval_s(); @@ -3463,6 +3809,9 @@ void StartPhotoIntervalRequest::MergeImpl(::google::protobuf::Message& to_msg, c ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_interval_s = from._internal_interval_s(); @@ -3491,13 +3840,18 @@ ::_pbi::CachedSize* StartPhotoIntervalRequest::AccessCachedSize() const { void StartPhotoIntervalRequest::InternalSwap(StartPhotoIntervalRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.interval_s_, other->_impl_.interval_s_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.interval_s_) + + sizeof(StartPhotoIntervalRequest::_impl_.interval_s_) + - PROTOBUF_FIELD_OFFSET(StartPhotoIntervalRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata StartPhotoIntervalRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[4]); + file_level_metadata_camera_2fcamera_2eproto[2]); } // =================================================================== @@ -3704,7 +4058,7 @@ void StartPhotoIntervalResponse::InternalSwap(StartPhotoIntervalResponse* PROTOB ::google::protobuf::Metadata StartPhotoIntervalResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[5]); + file_level_metadata_camera_2fcamera_2eproto[3]); } // =================================================================== @@ -3713,33 +4067,168 @@ class StopPhotoIntervalRequest::_Internal { }; StopPhotoIntervalRequest::StopPhotoIntervalRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { + : ::google::protobuf::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.StopPhotoIntervalRequest) } StopPhotoIntervalRequest::StopPhotoIntervalRequest( - ::google::protobuf::Arena* arena, - const StopPhotoIntervalRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - StopPhotoIntervalRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); + ::google::protobuf::Arena* arena, const StopPhotoIntervalRequest& from) + : StopPhotoIntervalRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE StopPhotoIntervalRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void StopPhotoIntervalRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +StopPhotoIntervalRequest::~StopPhotoIntervalRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StopPhotoIntervalRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void StopPhotoIntervalRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void StopPhotoIntervalRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.StopPhotoIntervalRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* StopPhotoIntervalRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StopPhotoIntervalRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_StopPhotoIntervalRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StopPhotoIntervalRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StopPhotoIntervalRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StopPhotoIntervalRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* StopPhotoIntervalRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.StopPhotoIntervalRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.StopPhotoIntervalRequest) + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.StopPhotoIntervalRequest) + return target; } +::size_t StopPhotoIntervalRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.StopPhotoIntervalRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} +const ::google::protobuf::Message::ClassData StopPhotoIntervalRequest::_class_data_ = { + StopPhotoIntervalRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* StopPhotoIntervalRequest::GetClassData() const { + return &_class_data_; +} +void StopPhotoIntervalRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.StopPhotoIntervalRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} +void StopPhotoIntervalRequest::CopyFrom(const StopPhotoIntervalRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.StopPhotoIntervalRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +PROTOBUF_NOINLINE bool StopPhotoIntervalRequest::IsInitialized() const { + return true; +} +::_pbi::CachedSize* StopPhotoIntervalRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void StopPhotoIntervalRequest::InternalSwap(StopPhotoIntervalRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} ::google::protobuf::Metadata StopPhotoIntervalRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[6]); + file_level_metadata_camera_2fcamera_2eproto[4]); } // =================================================================== @@ -3946,7 +4435,7 @@ void StopPhotoIntervalResponse::InternalSwap(StopPhotoIntervalResponse* PROTOBUF ::google::protobuf::Metadata StopPhotoIntervalResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[7]); + file_level_metadata_camera_2fcamera_2eproto[5]); } // =================================================================== @@ -3955,34 +4444,169 @@ class StartVideoRequest::_Internal { }; StartVideoRequest::StartVideoRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { + : ::google::protobuf::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.StartVideoRequest) } StartVideoRequest::StartVideoRequest( - ::google::protobuf::Arena* arena, - const StartVideoRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - StartVideoRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.StartVideoRequest) + ::google::protobuf::Arena* arena, const StartVideoRequest& from) + : StartVideoRequest(arena) { + MergeFrom(from); } +inline PROTOBUF_NDEBUG_INLINE StartVideoRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} +inline void StartVideoRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +StartVideoRequest::~StartVideoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StartVideoRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void StartVideoRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} +PROTOBUF_NOINLINE void StartVideoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.StartVideoRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} +const char* StartVideoRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} - - - -::google::protobuf::Metadata StartVideoRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[8]); -} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StartVideoRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_StartVideoRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StartVideoRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StartVideoRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StartVideoRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* StartVideoRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.StartVideoRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.StartVideoRequest) + return target; +} + +::size_t StartVideoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.StartVideoRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData StartVideoRequest::_class_data_ = { + StartVideoRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* StartVideoRequest::GetClassData() const { + return &_class_data_; +} + +void StartVideoRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.StartVideoRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void StartVideoRequest::CopyFrom(const StartVideoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.StartVideoRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool StartVideoRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* StartVideoRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void StartVideoRequest::InternalSwap(StartVideoRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::Metadata StartVideoRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[6]); +} // =================================================================== class StartVideoResponse::_Internal { @@ -4188,7 +4812,7 @@ void StartVideoResponse::InternalSwap(StartVideoResponse* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata StartVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[9]); + file_level_metadata_camera_2fcamera_2eproto[7]); } // =================================================================== @@ -4197,33 +4821,168 @@ class StopVideoRequest::_Internal { }; StopVideoRequest::StopVideoRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { + : ::google::protobuf::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.StopVideoRequest) } StopVideoRequest::StopVideoRequest( - ::google::protobuf::Arena* arena, - const StopVideoRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - StopVideoRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); + ::google::protobuf::Arena* arena, const StopVideoRequest& from) + : StopVideoRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE StopVideoRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void StopVideoRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +StopVideoRequest::~StopVideoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StopVideoRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void StopVideoRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void StopVideoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.StopVideoRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* StopVideoRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StopVideoRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_StopVideoRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StopVideoRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StopVideoRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StopVideoRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.StopVideoRequest) +::uint8_t* StopVideoRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.StopVideoRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.StopVideoRequest) + return target; } +::size_t StopVideoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.StopVideoRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} +const ::google::protobuf::Message::ClassData StopVideoRequest::_class_data_ = { + StopVideoRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* StopVideoRequest::GetClassData() const { + return &_class_data_; +} +void StopVideoRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.StopVideoRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} +void StopVideoRequest::CopyFrom(const StopVideoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.StopVideoRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +PROTOBUF_NOINLINE bool StopVideoRequest::IsInitialized() const { + return true; +} +::_pbi::CachedSize* StopVideoRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void StopVideoRequest::InternalSwap(StopVideoRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} ::google::protobuf::Metadata StopVideoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[10]); + file_level_metadata_camera_2fcamera_2eproto[8]); } // =================================================================== @@ -4430,7 +5189,7 @@ void StopVideoResponse::InternalSwap(StopVideoResponse* PROTOBUF_RESTRICT other) ::google::protobuf::Metadata StopVideoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[11]); + file_level_metadata_camera_2fcamera_2eproto[9]); } // =================================================================== @@ -4455,7 +5214,12 @@ inline PROTOBUF_NDEBUG_INLINE StartVideoStreamingRequest::Impl_::Impl_( inline void StartVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.stream_id_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, stream_id_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::stream_id_)); } StartVideoStreamingRequest::~StartVideoStreamingRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StartVideoStreamingRequest) @@ -4474,7 +5238,9 @@ PROTOBUF_NOINLINE void StartVideoStreamingRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.stream_id_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.stream_id_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.stream_id_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -4486,27 +5252,33 @@ const char* StartVideoStreamingRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StartVideoStreamingRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> StartVideoStreamingRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_StartVideoStreamingRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // int32 stream_id = 1; + // int32 stream_id = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StartVideoStreamingRequest, _impl_.stream_id_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.stream_id_)}}, + {16, 63, 0, PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.stream_id_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StartVideoStreamingRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // int32 stream_id = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // int32 stream_id = 2; {PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.stream_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, @@ -4522,10 +5294,17 @@ ::uint8_t* StartVideoStreamingRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { target = ::google::protobuf::internal::WireFormatLite:: WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // int32 stream_id = 2; + if (this->_internal_stream_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<2>( stream, this->_internal_stream_id(), target); } @@ -4546,7 +5325,13 @@ ::size_t StartVideoStreamingRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 stream_id = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // int32 stream_id = 2; if (this->_internal_stream_id() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_stream_id()); @@ -4571,6 +5356,9 @@ void StartVideoStreamingRequest::MergeImpl(::google::protobuf::Message& to_msg, ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_stream_id() != 0) { _this->_internal_set_stream_id(from._internal_stream_id()); } @@ -4594,13 +5382,18 @@ ::_pbi::CachedSize* StartVideoStreamingRequest::AccessCachedSize() const { void StartVideoStreamingRequest::InternalSwap(StartVideoStreamingRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.stream_id_, other->_impl_.stream_id_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.stream_id_) + + sizeof(StartVideoStreamingRequest::_impl_.stream_id_) + - PROTOBUF_FIELD_OFFSET(StartVideoStreamingRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata StartVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[12]); + file_level_metadata_camera_2fcamera_2eproto[10]); } // =================================================================== @@ -4807,7 +5600,7 @@ void StartVideoStreamingResponse::InternalSwap(StartVideoStreamingResponse* PROT ::google::protobuf::Metadata StartVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[13]); + file_level_metadata_camera_2fcamera_2eproto[11]); } // =================================================================== @@ -4832,7 +5625,12 @@ inline PROTOBUF_NDEBUG_INLINE StopVideoStreamingRequest::Impl_::Impl_( inline void StopVideoStreamingRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.stream_id_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, stream_id_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::stream_id_)); } StopVideoStreamingRequest::~StopVideoStreamingRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.StopVideoStreamingRequest) @@ -4851,7 +5649,9 @@ PROTOBUF_NOINLINE void StopVideoStreamingRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.stream_id_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.stream_id_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.stream_id_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -4863,27 +5663,33 @@ const char* StopVideoStreamingRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> StopVideoStreamingRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> StopVideoStreamingRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_StopVideoStreamingRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // int32 stream_id = 1; + // int32 stream_id = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StopVideoStreamingRequest, _impl_.stream_id_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.stream_id_)}}, + {16, 63, 0, PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.stream_id_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(StopVideoStreamingRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // int32 stream_id = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // int32 stream_id = 2; {PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.stream_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, @@ -4899,10 +5705,17 @@ ::uint8_t* StopVideoStreamingRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // int32 stream_id = 1; - if (this->_internal_stream_id() != 0) { + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { target = ::google::protobuf::internal::WireFormatLite:: WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // int32 stream_id = 2; + if (this->_internal_stream_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<2>( stream, this->_internal_stream_id(), target); } @@ -4923,7 +5736,13 @@ ::size_t StopVideoStreamingRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 stream_id = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // int32 stream_id = 2; if (this->_internal_stream_id() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_stream_id()); @@ -4948,6 +5767,9 @@ void StopVideoStreamingRequest::MergeImpl(::google::protobuf::Message& to_msg, c ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_stream_id() != 0) { _this->_internal_set_stream_id(from._internal_stream_id()); } @@ -4971,13 +5793,18 @@ ::_pbi::CachedSize* StopVideoStreamingRequest::AccessCachedSize() const { void StopVideoStreamingRequest::InternalSwap(StopVideoStreamingRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.stream_id_, other->_impl_.stream_id_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.stream_id_) + + sizeof(StopVideoStreamingRequest::_impl_.stream_id_) + - PROTOBUF_FIELD_OFFSET(StopVideoStreamingRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata StopVideoStreamingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[14]); + file_level_metadata_camera_2fcamera_2eproto[12]); } // =================================================================== @@ -5184,7 +6011,7 @@ void StopVideoStreamingResponse::InternalSwap(StopVideoStreamingResponse* PROTOB ::google::protobuf::Metadata StopVideoStreamingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[15]); + file_level_metadata_camera_2fcamera_2eproto[13]); } // =================================================================== @@ -5209,7 +6036,12 @@ inline PROTOBUF_NDEBUG_INLINE SetModeRequest::Impl_::Impl_( inline void SetModeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.mode_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, mode_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::mode_)); } SetModeRequest::~SetModeRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SetModeRequest) @@ -5228,7 +6060,9 @@ PROTOBUF_NOINLINE void SetModeRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.mode_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.mode_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.mode_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -5240,27 +6074,33 @@ const char* SetModeRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetModeRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> SetModeRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_SetModeRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Mode mode = 1; + // .mavsdk.rpc.camera.Mode mode = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetModeRequest, _impl_.mode_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.mode_)}}, + {16, 63, 0, PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.mode_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetModeRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.Mode mode = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.Mode mode = 2; {PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, @@ -5276,11 +6116,18 @@ ::uint8_t* SetModeRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.camera.Mode mode = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // .mavsdk.rpc.camera.Mode mode = 2; if (this->_internal_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_mode(), target); + 2, this->_internal_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -5300,7 +6147,13 @@ ::size_t SetModeRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.Mode mode = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // .mavsdk.rpc.camera.Mode mode = 2; if (this->_internal_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); @@ -5325,6 +6178,9 @@ void SetModeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::goog ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_mode() != 0) { _this->_internal_set_mode(from._internal_mode()); } @@ -5348,13 +6204,18 @@ ::_pbi::CachedSize* SetModeRequest::AccessCachedSize() const { void SetModeRequest::InternalSwap(SetModeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.mode_, other->_impl_.mode_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.mode_) + + sizeof(SetModeRequest::_impl_.mode_) + - PROTOBUF_FIELD_OFFSET(SetModeRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata SetModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[16]); + file_level_metadata_camera_2fcamera_2eproto[14]); } // =================================================================== @@ -5561,7 +6422,7 @@ void SetModeResponse::InternalSwap(SetModeResponse* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata SetModeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[17]); + file_level_metadata_camera_2fcamera_2eproto[15]); } // =================================================================== @@ -5586,7 +6447,12 @@ inline PROTOBUF_NDEBUG_INLINE ListPhotosRequest::Impl_::Impl_( inline void ListPhotosRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.photos_range_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, photos_range_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::photos_range_)); } ListPhotosRequest::~ListPhotosRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ListPhotosRequest) @@ -5605,7 +6471,9 @@ PROTOBUF_NOINLINE void ListPhotosRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.photos_range_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.photos_range_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.photos_range_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -5617,27 +6485,33 @@ const char* ListPhotosRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ListPhotosRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> ListPhotosRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_ListPhotosRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.PhotosRange photos_range = 1; + // .mavsdk.rpc.camera.PhotosRange photos_range = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ListPhotosRequest, _impl_.photos_range_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.photos_range_)}}, + {16, 63, 0, PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.photos_range_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ListPhotosRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.PhotosRange photos_range = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.PhotosRange photos_range = 2; {PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.photos_range_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, @@ -5653,11 +6527,18 @@ ::uint8_t* ListPhotosRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.camera.PhotosRange photos_range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // .mavsdk.rpc.camera.PhotosRange photos_range = 2; if (this->_internal_photos_range() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_photos_range(), target); + 2, this->_internal_photos_range(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -5677,7 +6558,13 @@ ::size_t ListPhotosRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.PhotosRange photos_range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // .mavsdk.rpc.camera.PhotosRange photos_range = 2; if (this->_internal_photos_range() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_photos_range()); @@ -5702,6 +6589,9 @@ void ListPhotosRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::g ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_photos_range() != 0) { _this->_internal_set_photos_range(from._internal_photos_range()); } @@ -5725,13 +6615,18 @@ ::_pbi::CachedSize* ListPhotosRequest::AccessCachedSize() const { void ListPhotosRequest::InternalSwap(ListPhotosRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.photos_range_, other->_impl_.photos_range_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.photos_range_) + + sizeof(ListPhotosRequest::_impl_.photos_range_) + - PROTOBUF_FIELD_OFFSET(ListPhotosRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata ListPhotosRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[18]); + file_level_metadata_camera_2fcamera_2eproto[16]); } // =================================================================== @@ -5965,28 +6860,28 @@ void ListPhotosResponse::InternalSwap(ListPhotosResponse* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata ListPhotosResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[19]); + file_level_metadata_camera_2fcamera_2eproto[17]); } // =================================================================== -class SubscribeInformationRequest::_Internal { +class SubscribeCameraListRequest::_Internal { public: }; -SubscribeInformationRequest::SubscribeInformationRequest(::google::protobuf::Arena* arena) +SubscribeCameraListRequest::SubscribeCameraListRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeInformationRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeCameraListRequest) } -SubscribeInformationRequest::SubscribeInformationRequest( +SubscribeCameraListRequest::SubscribeCameraListRequest( ::google::protobuf::Arena* arena, - const SubscribeInformationRequest& from) + const SubscribeCameraListRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeInformationRequest* const _this = this; + SubscribeCameraListRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeInformationRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeCameraListRequest) } @@ -5997,76 +6892,76 @@ SubscribeInformationRequest::SubscribeInformationRequest( -::google::protobuf::Metadata SubscribeInformationRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeCameraListRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[20]); + file_level_metadata_camera_2fcamera_2eproto[18]); } // =================================================================== -class InformationResponse::_Internal { +class CameraListResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(InformationResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::Information& information(const InformationResponse* msg); - static void set_has_information(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(CameraListResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraList& camera_list(const CameraListResponse* msg); + static void set_has_camera_list(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::Information& InformationResponse::_Internal::information(const InformationResponse* msg) { - return *msg->_impl_.information_; +const ::mavsdk::rpc::camera::CameraList& CameraListResponse::_Internal::camera_list(const CameraListResponse* msg) { + return *msg->_impl_.camera_list_; } -InformationResponse::InformationResponse(::google::protobuf::Arena* arena) +CameraListResponse::CameraListResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.InformationResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.CameraListResponse) } -inline PROTOBUF_NDEBUG_INLINE InformationResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE CameraListResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -InformationResponse::InformationResponse( +CameraListResponse::CameraListResponse( ::google::protobuf::Arena* arena, - const InformationResponse& from) + const CameraListResponse& from) : ::google::protobuf::Message(arena) { - InformationResponse* const _this = this; + CameraListResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.information_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::Information>(arena, *from._impl_.information_) + _impl_.camera_list_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraList>(arena, *from._impl_.camera_list_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.InformationResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.CameraListResponse) } -inline PROTOBUF_NDEBUG_INLINE InformationResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE CameraListResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void InformationResponse::SharedCtor(::_pb::Arena* arena) { +inline void CameraListResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.information_ = {}; + _impl_.camera_list_ = {}; } -InformationResponse::~InformationResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.InformationResponse) +CameraListResponse::~CameraListResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.CameraListResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void InformationResponse::SharedDtor() { +inline void CameraListResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.information_; + delete _impl_.camera_list_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void InformationResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.InformationResponse) +PROTOBUF_NOINLINE void CameraListResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.CameraListResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -6074,14 +6969,14 @@ PROTOBUF_NOINLINE void InformationResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.information_ != nullptr); - _impl_.information_->Clear(); + ABSL_DCHECK(_impl_.camera_list_ != nullptr); + _impl_.camera_list_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* InformationResponse::_InternalParse( +const char* CameraListResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -6089,9 +6984,9 @@ const char* InformationResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> InformationResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraListResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(InformationResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(CameraListResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -6100,37 +6995,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> InformationResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_InformationResponse_default_instance_._instance, + &_CameraListResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Information information = 1; + // .mavsdk.rpc.camera.CameraList camera_list = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(InformationResponse, _impl_.information_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(CameraListResponse, _impl_.camera_list_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.Information information = 1; - {PROTOBUF_FIELD_OFFSET(InformationResponse, _impl_.information_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.camera.CameraList camera_list = 1; + {PROTOBUF_FIELD_OFFSET(CameraListResponse, _impl_.camera_list_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Information>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraList>()}, }}, {{ }}, }; -::uint8_t* InformationResponse::_InternalSerialize( +::uint8_t* CameraListResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.InformationResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.CameraListResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.Information information = 1; + // .mavsdk.rpc.camera.CameraList camera_list = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::information(this), - _Internal::information(this).GetCachedSize(), target, stream); + 1, _Internal::camera_list(this), + _Internal::camera_list(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -6138,159 +7033,131 @@ ::uint8_t* InformationResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.InformationResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.CameraListResponse) return target; } -::size_t InformationResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.InformationResponse) +::size_t CameraListResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.CameraListResponse) ::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.Information information = 1; + // .mavsdk.rpc.camera.CameraList camera_list = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.information_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_list_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData InformationResponse::_class_data_ = { - InformationResponse::MergeImpl, +const ::google::protobuf::Message::ClassData CameraListResponse::_class_data_ = { + CameraListResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* InformationResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* CameraListResponse::GetClassData() const { return &_class_data_; } -void InformationResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.InformationResponse) +void CameraListResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.CameraListResponse) 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_information()->::mavsdk::rpc::camera::Information::MergeFrom( - from._internal_information()); + _this->_internal_mutable_camera_list()->::mavsdk::rpc::camera::CameraList::MergeFrom( + from._internal_camera_list()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void InformationResponse::CopyFrom(const InformationResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.InformationResponse) +void CameraListResponse::CopyFrom(const CameraListResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.CameraListResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool InformationResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool CameraListResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* InformationResponse::AccessCachedSize() const { +::_pbi::CachedSize* CameraListResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void InformationResponse::InternalSwap(InformationResponse* PROTOBUF_RESTRICT other) { +void CameraListResponse::InternalSwap(CameraListResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.information_, other->_impl_.information_); -} - -::google::protobuf::Metadata InformationResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[21]); -} -// =================================================================== - -class SubscribeModeRequest::_Internal { - public: -}; - -SubscribeModeRequest::SubscribeModeRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeModeRequest) -} -SubscribeModeRequest::SubscribeModeRequest( - ::google::protobuf::Arena* arena, - const SubscribeModeRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeModeRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeModeRequest) + swap(_impl_.camera_list_, other->_impl_.camera_list_); } - - - - - - - - -::google::protobuf::Metadata SubscribeModeRequest::GetMetadata() const { +::google::protobuf::Metadata CameraListResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[22]); + file_level_metadata_camera_2fcamera_2eproto[19]); } // =================================================================== -class ModeResponse::_Internal { +class ModeInfo::_Internal { public: }; -ModeResponse::ModeResponse(::google::protobuf::Arena* arena) +ModeInfo::ModeInfo(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ModeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ModeInfo) } -ModeResponse::ModeResponse( - ::google::protobuf::Arena* arena, const ModeResponse& from) - : ModeResponse(arena) { +ModeInfo::ModeInfo( + ::google::protobuf::Arena* arena, const ModeInfo& from) + : ModeInfo(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE ModeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ModeInfo::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ModeResponse::SharedCtor(::_pb::Arena* arena) { +inline void ModeInfo::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.mode_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, mode_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::mode_)); } -ModeResponse::~ModeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ModeResponse) +ModeInfo::~ModeInfo() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ModeInfo) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ModeResponse::SharedDtor() { +inline void ModeInfo::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ModeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ModeResponse) +PROTOBUF_NOINLINE void ModeInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ModeInfo) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.mode_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.mode_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.mode_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ModeResponse::_InternalParse( +const char* ModeInfo::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -6298,28 +7165,34 @@ const char* ModeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ModeResponse::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> ModeInfo::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_ModeResponse_default_instance_._instance, + &_ModeInfo_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Mode mode = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ModeResponse, _impl_.mode_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_.mode_)}}, + // .mavsdk.rpc.camera.Mode mode = 2; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ModeInfo, _impl_.mode_), 63>(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.mode_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ModeInfo, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.Mode mode = 1; - {PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_.mode_), 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.Mode mode = 2; + {PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, // no aux_entries @@ -6327,18 +7200,25 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ModeResponse::_table_ = { }}, }; -::uint8_t* ModeResponse::_InternalSerialize( +::uint8_t* ModeInfo::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ModeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ModeInfo) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.camera.Mode mode = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // .mavsdk.rpc.camera.Mode mode = 2; if (this->_internal_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_mode(), target); + 2, this->_internal_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -6346,19 +7226,25 @@ ::uint8_t* ModeResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ModeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ModeInfo) return target; } -::size_t ModeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ModeResponse) +::size_t ModeInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ModeInfo) ::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.Mode mode = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // .mavsdk.rpc.camera.Mode mode = 2; if (this->_internal_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); @@ -6367,73 +7253,81 @@ ::size_t ModeResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ModeResponse::_class_data_ = { - ModeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ModeInfo::_class_data_ = { + ModeInfo::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ModeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ModeInfo::GetClassData() const { return &_class_data_; } -void ModeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ModeResponse) +void ModeInfo::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ModeInfo) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_mode() != 0) { _this->_internal_set_mode(from._internal_mode()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ModeResponse::CopyFrom(const ModeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ModeResponse) +void ModeInfo::CopyFrom(const ModeInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ModeInfo) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ModeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ModeInfo::IsInitialized() const { return true; } -::_pbi::CachedSize* ModeResponse::AccessCachedSize() const { +::_pbi::CachedSize* ModeInfo::AccessCachedSize() const { return &_impl_._cached_size_; } -void ModeResponse::InternalSwap(ModeResponse* PROTOBUF_RESTRICT other) { +void ModeInfo::InternalSwap(ModeInfo* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.mode_, other->_impl_.mode_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.mode_) + + sizeof(ModeInfo::_impl_.mode_) + - PROTOBUF_FIELD_OFFSET(ModeInfo, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } -::google::protobuf::Metadata ModeResponse::GetMetadata() const { +::google::protobuf::Metadata ModeInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[23]); + file_level_metadata_camera_2fcamera_2eproto[20]); } // =================================================================== -class SubscribeVideoStreamInfoRequest::_Internal { +class SubscribeModeRequest::_Internal { public: }; -SubscribeVideoStreamInfoRequest::SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena) +SubscribeModeRequest::SubscribeModeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeModeRequest) } -SubscribeVideoStreamInfoRequest::SubscribeVideoStreamInfoRequest( +SubscribeModeRequest::SubscribeModeRequest( ::google::protobuf::Arena* arena, - const SubscribeVideoStreamInfoRequest& from) + const SubscribeModeRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeVideoStreamInfoRequest* const _this = this; + SubscribeModeRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeModeRequest) } @@ -6444,65 +7338,307 @@ SubscribeVideoStreamInfoRequest::SubscribeVideoStreamInfoRequest( -::google::protobuf::Metadata SubscribeVideoStreamInfoRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[24]); + file_level_metadata_camera_2fcamera_2eproto[21]); } // =================================================================== -class VideoStreamInfoResponse::_Internal { +class ModeResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info(const VideoStreamInfoResponse* msg); - static void set_has_video_stream_info(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::ModeInfo& mode_info(const ModeResponse* msg); + static void set_has_mode_info(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::_Internal::video_stream_info(const VideoStreamInfoResponse* msg) { - return *msg->_impl_.video_stream_info_; +const ::mavsdk::rpc::camera::ModeInfo& ModeResponse::_Internal::mode_info(const ModeResponse* msg) { + return *msg->_impl_.mode_info_; } -VideoStreamInfoResponse::VideoStreamInfoResponse(::google::protobuf::Arena* arena) +ModeResponse::ModeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.VideoStreamInfoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ModeResponse) } -inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ModeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -VideoStreamInfoResponse::VideoStreamInfoResponse( +ModeResponse::ModeResponse( ::google::protobuf::Arena* arena, - const VideoStreamInfoResponse& from) + const ModeResponse& from) : ::google::protobuf::Message(arena) { - VideoStreamInfoResponse* const _this = this; + ModeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.video_stream_info_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(arena, *from._impl_.video_stream_info_) + _impl_.mode_info_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::ModeInfo>(arena, *from._impl_.mode_info_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.VideoStreamInfoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ModeResponse) } -inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ModeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void VideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { +inline void ModeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.video_stream_info_ = {}; + _impl_.mode_info_ = {}; } -VideoStreamInfoResponse::~VideoStreamInfoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.VideoStreamInfoResponse) +ModeResponse::~ModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ModeResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ModeResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.mode_info_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ModeResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.mode_info_ != nullptr); + _impl_.mode_info_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ModeResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ModeResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ModeResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.ModeInfo mode_info = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_.mode_info_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.ModeInfo mode_info = 1; + {PROTOBUF_FIELD_OFFSET(ModeResponse, _impl_.mode_info_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::ModeInfo>()}, + }}, {{ + }}, +}; + +::uint8_t* ModeResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ModeResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.camera.ModeInfo mode_info = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::mode_info(this), + _Internal::mode_info(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ModeResponse) + return target; +} + +::size_t ModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ModeResponse) + ::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.ModeInfo mode_info = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.mode_info_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ModeResponse::_class_data_ = { + ModeResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ModeResponse::GetClassData() const { + return &_class_data_; +} + +void ModeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ModeResponse) + 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_mode_info()->::mavsdk::rpc::camera::ModeInfo::MergeFrom( + from._internal_mode_info()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ModeResponse::CopyFrom(const ModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ModeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ModeResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ModeResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ModeResponse::InternalSwap(ModeResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.mode_info_, other->_impl_.mode_info_); +} + +::google::protobuf::Metadata ModeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[22]); +} +// =================================================================== + +class SubscribeVideoStreamInfoRequest::_Internal { + public: +}; + +SubscribeVideoStreamInfoRequest::SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) +} +SubscribeVideoStreamInfoRequest::SubscribeVideoStreamInfoRequest( + ::google::protobuf::Arena* arena, + const SubscribeVideoStreamInfoRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeVideoStreamInfoRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeVideoStreamInfoRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[23]); +} +// =================================================================== + +class VideoStreamInfoResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(VideoStreamInfoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info(const VideoStreamInfoResponse* msg); + static void set_has_video_stream_info(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::VideoStreamInfo& VideoStreamInfoResponse::_Internal::video_stream_info(const VideoStreamInfoResponse* msg) { + return *msg->_impl_.video_stream_info_; +} +VideoStreamInfoResponse::VideoStreamInfoResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.VideoStreamInfoResponse) +} +inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +VideoStreamInfoResponse::VideoStreamInfoResponse( + ::google::protobuf::Arena* arena, + const VideoStreamInfoResponse& from) + : ::google::protobuf::Message(arena) { + VideoStreamInfoResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.video_stream_info_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(arena, *from._impl_.video_stream_info_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.VideoStreamInfoResponse) +} +inline PROTOBUF_NDEBUG_INLINE VideoStreamInfoResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void VideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.video_stream_info_ = {}; +} +VideoStreamInfoResponse::~VideoStreamInfoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.VideoStreamInfoResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } @@ -6654,7 +7790,7 @@ void VideoStreamInfoResponse::InternalSwap(VideoStreamInfoResponse* PROTOBUF_RES ::google::protobuf::Metadata VideoStreamInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[25]); + file_level_metadata_camera_2fcamera_2eproto[24]); } // =================================================================== @@ -6689,7 +7825,7 @@ SubscribeCaptureInfoRequest::SubscribeCaptureInfoRequest( ::google::protobuf::Metadata SubscribeCaptureInfoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[26]); + file_level_metadata_camera_2fcamera_2eproto[25]); } // =================================================================== @@ -6896,7 +8032,7 @@ void CaptureInfoResponse::InternalSwap(CaptureInfoResponse* PROTOBUF_RESTRICT ot ::google::protobuf::Metadata CaptureInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[27]); + file_level_metadata_camera_2fcamera_2eproto[26]); } // =================================================================== @@ -6931,7 +8067,7 @@ SubscribeStatusRequest::SubscribeStatusRequest( ::google::protobuf::Metadata SubscribeStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[28]); + file_level_metadata_camera_2fcamera_2eproto[27]); } // =================================================================== @@ -7138,7 +8274,7 @@ void StatusResponse::InternalSwap(StatusResponse* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata StatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[29]); + file_level_metadata_camera_2fcamera_2eproto[28]); } // =================================================================== @@ -7173,7 +8309,7 @@ SubscribeCurrentSettingsRequest::SubscribeCurrentSettingsRequest( ::google::protobuf::Metadata SubscribeCurrentSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[30]); + file_level_metadata_camera_2fcamera_2eproto[29]); } // =================================================================== @@ -7356,7 +8492,7 @@ void CurrentSettingsResponse::InternalSwap(CurrentSettingsResponse* PROTOBUF_RES ::google::protobuf::Metadata CurrentSettingsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[31]); + file_level_metadata_camera_2fcamera_2eproto[30]); } // =================================================================== @@ -7391,7 +8527,7 @@ SubscribePossibleSettingOptionsRequest::SubscribePossibleSettingOptionsRequest( ::google::protobuf::Metadata SubscribePossibleSettingOptionsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[32]); + file_level_metadata_camera_2fcamera_2eproto[31]); } // =================================================================== @@ -7574,7 +8710,7 @@ void PossibleSettingOptionsResponse::InternalSwap(PossibleSettingOptionsResponse ::google::protobuf::Metadata PossibleSettingOptionsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[33]); + file_level_metadata_camera_2fcamera_2eproto[32]); } // =================================================================== @@ -7616,6 +8752,7 @@ SetSettingRequest::SetSettingRequest( _impl_.setting_ = (cached_has_bits & 0x00000001u) ? CreateMaybeMessage<::mavsdk::rpc::camera::Setting>(arena, *from._impl_.setting_) : nullptr; + _impl_.camera_id_ = from._impl_.camera_id_; // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SetSettingRequest) } @@ -7626,7 +8763,12 @@ inline PROTOBUF_NDEBUG_INLINE SetSettingRequest::Impl_::Impl_( inline void SetSettingRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.setting_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, setting_), + 0, + offsetof(Impl_, camera_id_) - + offsetof(Impl_, setting_) + + sizeof(Impl_::camera_id_)); } SetSettingRequest::~SetSettingRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SetSettingRequest) @@ -7651,6 +8793,7 @@ PROTOBUF_NOINLINE void SetSettingRequest::Clear() { ABSL_DCHECK(_impl_.setting_ != nullptr); _impl_.setting_->Clear(); } + _impl_.camera_id_ = 0; _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -7663,28 +8806,34 @@ const char* SetSettingRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetSettingRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 1, 0, 2> SetSettingRequest::_table_ = { { PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_._has_bits_), 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), &_SetSettingRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Setting setting = 1; + // .mavsdk.rpc.camera.Setting setting = 2; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.setting_)}}, + {18, 0, 0, PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.setting_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetSettingRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.Setting setting = 1; - {PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.setting_), _Internal::kHasBitsOffset + 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.camera_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.Setting setting = 2; + {PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.setting_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, @@ -7699,11 +8848,18 @@ ::uint8_t* SetSettingRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.Setting setting = 1; + // .mavsdk.rpc.camera.Setting setting = 2; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::setting(this), + 2, _Internal::setting(this), _Internal::setting(this).GetCachedSize(), target, stream); } @@ -7724,13 +8880,19 @@ ::size_t SetSettingRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.Setting setting = 1; + // .mavsdk.rpc.camera.Setting setting = 2; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.setting_); } + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } @@ -7754,6 +8916,9 @@ void SetSettingRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::g _this->_internal_mutable_setting()->::mavsdk::rpc::camera::Setting::MergeFrom( from._internal_setting()); } + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -7775,13 +8940,18 @@ void SetSettingRequest::InternalSwap(SetSettingRequest* PROTOBUF_RESTRICT other) using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.setting_, other->_impl_.setting_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.camera_id_) + + sizeof(SetSettingRequest::_impl_.camera_id_) + - PROTOBUF_FIELD_OFFSET(SetSettingRequest, _impl_.setting_)>( + reinterpret_cast(&_impl_.setting_), + reinterpret_cast(&other->_impl_.setting_)); } ::google::protobuf::Metadata SetSettingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[34]); + file_level_metadata_camera_2fcamera_2eproto[33]); } // =================================================================== @@ -7988,88 +9158,55 @@ void SetSettingResponse::InternalSwap(SetSettingResponse* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata SetSettingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[35]); + file_level_metadata_camera_2fcamera_2eproto[34]); } // =================================================================== -class GetSettingRequest::_Internal { +class GetModeRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::Setting& setting(const GetSettingRequest* msg); - static void set_has_setting(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::Setting& GetSettingRequest::_Internal::setting(const GetSettingRequest* msg) { - return *msg->_impl_.setting_; -} -GetSettingRequest::GetSettingRequest(::google::protobuf::Arena* arena) +GetModeRequest::GetModeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetSettingRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetModeRequest) } -inline PROTOBUF_NDEBUG_INLINE GetSettingRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -GetSettingRequest::GetSettingRequest( - ::google::protobuf::Arena* arena, - const GetSettingRequest& from) - : ::google::protobuf::Message(arena) { - GetSettingRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.setting_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::Setting>(arena, *from._impl_.setting_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetSettingRequest) +GetModeRequest::GetModeRequest( + ::google::protobuf::Arena* arena, const GetModeRequest& from) + : GetModeRequest(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE GetSettingRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetModeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void GetSettingRequest::SharedCtor(::_pb::Arena* arena) { +inline void GetModeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.setting_ = {}; + _impl_.camera_id_ = {}; } -GetSettingRequest::~GetSettingRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetSettingRequest) +GetModeRequest::~GetModeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetModeRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void GetSettingRequest::SharedDtor() { +inline void GetModeRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.setting_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void GetSettingRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetSettingRequest) +PROTOBUF_NOINLINE void GetModeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetModeRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.setting_ != nullptr); - _impl_.setting_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* GetSettingRequest::_InternalParse( +const char* GetModeRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8077,48 +9214,47 @@ const char* GetSettingRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GetSettingRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetModeRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_GetSettingRequest_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GetModeRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Setting setting = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.setting_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetModeRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetModeRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.Setting setting = 1; - {PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.setting_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, - }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(GetModeRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* GetSettingRequest::_InternalSerialize( +::uint8_t* GetModeRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetSettingRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetModeRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.Setting setting = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::setting(this), - _Internal::setting(this).GetCachedSize(), target, stream); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8126,179 +9262,121 @@ ::uint8_t* GetSettingRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetSettingRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetModeRequest) return target; } -::size_t GetSettingRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetSettingRequest) +::size_t GetModeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetModeRequest) ::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.Setting setting = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.setting_); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData GetSettingRequest::_class_data_ = { - GetSettingRequest::MergeImpl, +const ::google::protobuf::Message::ClassData GetModeRequest::_class_data_ = { + GetModeRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* GetSettingRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetModeRequest::GetClassData() const { return &_class_data_; } -void GetSettingRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetSettingRequest) +void GetModeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetModeRequest) 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_setting()->::mavsdk::rpc::camera::Setting::MergeFrom( - from._internal_setting()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void GetSettingRequest::CopyFrom(const GetSettingRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetSettingRequest) +void GetModeRequest::CopyFrom(const GetModeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetModeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool GetSettingRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool GetModeRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* GetSettingRequest::AccessCachedSize() const { +::_pbi::CachedSize* GetModeRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void GetSettingRequest::InternalSwap(GetSettingRequest* PROTOBUF_RESTRICT other) { +void GetModeRequest::InternalSwap(GetModeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.setting_, other->_impl_.setting_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); } -::google::protobuf::Metadata GetSettingRequest::GetMetadata() const { +::google::protobuf::Metadata GetModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[36]); + file_level_metadata_camera_2fcamera_2eproto[35]); } // =================================================================== -class GetSettingResponse::_Internal { +class GetModeResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const GetSettingResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } - static const ::mavsdk::rpc::camera::Setting& setting(const GetSettingResponse* msg); - static void set_has_setting(HasBits* has_bits) { - (*has_bits)[0] |= 2u; - } }; -const ::mavsdk::rpc::camera::CameraResult& GetSettingResponse::_Internal::camera_result(const GetSettingResponse* msg) { - return *msg->_impl_.camera_result_; -} -const ::mavsdk::rpc::camera::Setting& GetSettingResponse::_Internal::setting(const GetSettingResponse* msg) { - return *msg->_impl_.setting_; -} -GetSettingResponse::GetSettingResponse(::google::protobuf::Arena* arena) +GetModeResponse::GetModeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetSettingResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetModeResponse) } -inline PROTOBUF_NDEBUG_INLINE GetSettingResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -GetSettingResponse::GetSettingResponse( - ::google::protobuf::Arena* arena, - const GetSettingResponse& from) - : ::google::protobuf::Message(arena) { - GetSettingResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) - : nullptr; - _impl_.setting_ = (cached_has_bits & 0x00000002u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::Setting>(arena, *from._impl_.setting_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetSettingResponse) +GetModeResponse::GetModeResponse( + ::google::protobuf::Arena* arena, const GetModeResponse& from) + : GetModeResponse(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE GetSettingResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetModeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void GetSettingResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetModeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, camera_result_), - 0, - offsetof(Impl_, setting_) - - offsetof(Impl_, camera_result_) + - sizeof(Impl_::setting_)); + _impl_.mode_ = {}; } -GetSettingResponse::~GetSettingResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetSettingResponse) +GetModeResponse::~GetModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetModeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void GetSettingResponse::SharedDtor() { +inline void GetModeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; - delete _impl_.setting_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void GetSettingResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetSettingResponse) +PROTOBUF_NOINLINE void GetModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetModeResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000003u) { - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_result_ != nullptr); - _impl_.camera_result_->Clear(); - } - if (cached_has_bits & 0x00000002u) { - ABSL_DCHECK(_impl_.setting_ != nullptr); - _impl_.setting_->Clear(); - } - } - _impl_._has_bits_.Clear(); + _impl_.mode_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* GetSettingResponse::_InternalParse( +const char* GetModeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8306,62 +9384,47 @@ const char* GetSettingResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetSettingResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetModeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ - 2, 8, // max_field_number, fast_idx_mask + 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967292, // skipmap + 4294967294, // skipmap offsetof(decltype(_table_), field_entries), - 2, // num_field_entries - 2, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_GetSettingResponse_default_instance_._instance, + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GetModeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.Setting setting = 2; - {::_pbi::TcParser::FastMtS1, - {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_)}}, - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_)}}, + // .mavsdk.rpc.camera.Mode mode = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetModeResponse, _impl_.mode_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetModeResponse, _impl_.mode_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.camera.Setting setting = 2; - {PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_), _Internal::kHasBitsOffset + 1, 1, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, - }}, {{ + // .mavsdk.rpc.camera.Mode mode = 1; + {PROTOBUF_FIELD_OFFSET(GetModeResponse, _impl_.mode_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* GetSettingResponse::_InternalSerialize( +::uint8_t* GetModeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetSettingResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetModeResponse) ::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 = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); - } - - // .mavsdk.rpc.camera.Setting setting = 2; - if (cached_has_bits & 0x00000002u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 2, _Internal::setting(this), - _Internal::setting(this).GetCachedSize(), target, stream); + // .mavsdk.rpc.camera.Mode mode = 1; + if (this->_internal_mode() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8369,144 +9432,121 @@ ::uint8_t* GetSettingResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetSettingResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetModeResponse) return target; } -::size_t GetSettingResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetSettingResponse) +::size_t GetModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetModeResponse) ::size_t total_size = 0; ::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 & 0x00000003u) { - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); - } - - // .mavsdk.rpc.camera.Setting setting = 2; - if (cached_has_bits & 0x00000002u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.setting_); - } - + // .mavsdk.rpc.camera.Mode mode = 1; + if (this->_internal_mode() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_mode()); } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData GetSettingResponse::_class_data_ = { - GetSettingResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetModeResponse::_class_data_ = { + GetModeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* GetSettingResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetModeResponse::GetClassData() const { return &_class_data_; } -void GetSettingResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetSettingResponse) +void GetModeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetModeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = from._impl_._has_bits_[0]; - if (cached_has_bits & 0x00000003u) { - if (cached_has_bits & 0x00000001u) { - _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( - from._internal_camera_result()); - } - if (cached_has_bits & 0x00000002u) { - _this->_internal_mutable_setting()->::mavsdk::rpc::camera::Setting::MergeFrom( - from._internal_setting()); - } + if (from._internal_mode() != 0) { + _this->_internal_set_mode(from._internal_mode()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void GetSettingResponse::CopyFrom(const GetSettingResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetSettingResponse) +void GetModeResponse::CopyFrom(const GetModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetModeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool GetSettingResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetModeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* GetSettingResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetModeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void GetSettingResponse::InternalSwap(GetSettingResponse* PROTOBUF_RESTRICT other) { +void GetModeResponse::InternalSwap(GetModeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_) - + sizeof(GetSettingResponse::_impl_.setting_) - - PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_)>( - reinterpret_cast(&_impl_.camera_result_), - reinterpret_cast(&other->_impl_.camera_result_)); + swap(_impl_.mode_, other->_impl_.mode_); } -::google::protobuf::Metadata GetSettingResponse::GetMetadata() const { +::google::protobuf::Metadata GetModeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[37]); + file_level_metadata_camera_2fcamera_2eproto[36]); } // =================================================================== -class FormatStorageRequest::_Internal { +class GetVideoStreamInfoRequest::_Internal { public: }; -FormatStorageRequest::FormatStorageRequest(::google::protobuf::Arena* arena) +GetVideoStreamInfoRequest::GetVideoStreamInfoRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FormatStorageRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetVideoStreamInfoRequest) } -FormatStorageRequest::FormatStorageRequest( - ::google::protobuf::Arena* arena, const FormatStorageRequest& from) - : FormatStorageRequest(arena) { +GetVideoStreamInfoRequest::GetVideoStreamInfoRequest( + ::google::protobuf::Arena* arena, const GetVideoStreamInfoRequest& from) + : GetVideoStreamInfoRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE FormatStorageRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetVideoStreamInfoRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void FormatStorageRequest::SharedCtor(::_pb::Arena* arena) { +inline void GetVideoStreamInfoRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.storage_id_ = {}; + _impl_.camera_id_ = {}; } -FormatStorageRequest::~FormatStorageRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FormatStorageRequest) +GetVideoStreamInfoRequest::~GetVideoStreamInfoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetVideoStreamInfoRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FormatStorageRequest::SharedDtor() { +inline void GetVideoStreamInfoRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void FormatStorageRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FormatStorageRequest) +PROTOBUF_NOINLINE void GetVideoStreamInfoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetVideoStreamInfoRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.storage_id_ = 0; + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FormatStorageRequest::_InternalParse( +const char* GetVideoStreamInfoRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8514,7 +9554,7 @@ const char* FormatStorageRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FormatStorageRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetVideoStreamInfoRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -8525,17 +9565,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FormatStorageRequest::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_FormatStorageRequest_default_instance_._instance, + &_GetVideoStreamInfoRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // int32 storage_id = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FormatStorageRequest, _impl_.storage_id_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.storage_id_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetVideoStreamInfoRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // int32 storage_id = 1; - {PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.storage_id_), 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoRequest, _impl_.camera_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, // no aux_entries @@ -8543,18 +9583,18 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FormatStorageRequest::_table_ = { }}, }; -::uint8_t* FormatStorageRequest::_InternalSerialize( +::uint8_t* GetVideoStreamInfoRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FormatStorageRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetVideoStreamInfoRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { target = ::google::protobuf::internal::WireFormatLite:: WriteInt32ToArrayWithField<1>( - stream, this->_internal_storage_id(), target); + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8562,139 +9602,139 @@ ::uint8_t* FormatStorageRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FormatStorageRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetVideoStreamInfoRequest) return target; } -::size_t FormatStorageRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FormatStorageRequest) +::size_t GetVideoStreamInfoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetVideoStreamInfoRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 storage_id = 1; - if (this->_internal_storage_id() != 0) { + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( - this->_internal_storage_id()); + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FormatStorageRequest::_class_data_ = { - FormatStorageRequest::MergeImpl, +const ::google::protobuf::Message::ClassData GetVideoStreamInfoRequest::_class_data_ = { + GetVideoStreamInfoRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FormatStorageRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetVideoStreamInfoRequest::GetClassData() const { return &_class_data_; } -void FormatStorageRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FormatStorageRequest) +void GetVideoStreamInfoRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetVideoStreamInfoRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_storage_id() != 0) { - _this->_internal_set_storage_id(from._internal_storage_id()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void FormatStorageRequest::CopyFrom(const FormatStorageRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FormatStorageRequest) +void GetVideoStreamInfoRequest::CopyFrom(const GetVideoStreamInfoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetVideoStreamInfoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FormatStorageRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool GetVideoStreamInfoRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* FormatStorageRequest::AccessCachedSize() const { +::_pbi::CachedSize* GetVideoStreamInfoRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void FormatStorageRequest::InternalSwap(FormatStorageRequest* PROTOBUF_RESTRICT other) { +void GetVideoStreamInfoRequest::InternalSwap(GetVideoStreamInfoRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.storage_id_, other->_impl_.storage_id_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); } -::google::protobuf::Metadata FormatStorageRequest::GetMetadata() const { +::google::protobuf::Metadata GetVideoStreamInfoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[38]); + file_level_metadata_camera_2fcamera_2eproto[37]); } // =================================================================== -class FormatStorageResponse::_Internal { +class GetVideoStreamInfoResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FormatStorageResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info(const GetVideoStreamInfoResponse* msg); + static void set_has_video_stream_info(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& FormatStorageResponse::_Internal::camera_result(const FormatStorageResponse* msg) { - return *msg->_impl_.camera_result_; +const ::mavsdk::rpc::camera::VideoStreamInfo& GetVideoStreamInfoResponse::_Internal::video_stream_info(const GetVideoStreamInfoResponse* msg) { + return *msg->_impl_.video_stream_info_; } -FormatStorageResponse::FormatStorageResponse(::google::protobuf::Arena* arena) +GetVideoStreamInfoResponse::GetVideoStreamInfoResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FormatStorageResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetVideoStreamInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE FormatStorageResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetVideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -FormatStorageResponse::FormatStorageResponse( +GetVideoStreamInfoResponse::GetVideoStreamInfoResponse( ::google::protobuf::Arena* arena, - const FormatStorageResponse& from) + const GetVideoStreamInfoResponse& from) : ::google::protobuf::Message(arena) { - FormatStorageResponse* const _this = this; + GetVideoStreamInfoResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + _impl_.video_stream_info_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(arena, *from._impl_.video_stream_info_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FormatStorageResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetVideoStreamInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE FormatStorageResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetVideoStreamInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void FormatStorageResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetVideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + _impl_.video_stream_info_ = {}; } -FormatStorageResponse::~FormatStorageResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FormatStorageResponse) +GetVideoStreamInfoResponse::~GetVideoStreamInfoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetVideoStreamInfoResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FormatStorageResponse::SharedDtor() { +inline void GetVideoStreamInfoResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; + delete _impl_.video_stream_info_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void FormatStorageResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FormatStorageResponse) +PROTOBUF_NOINLINE void GetVideoStreamInfoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetVideoStreamInfoResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8702,14 +9742,14 @@ PROTOBUF_NOINLINE void FormatStorageResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_result_ != nullptr); - _impl_.camera_result_->Clear(); + ABSL_DCHECK(_impl_.video_stream_info_ != nullptr); + _impl_.video_stream_info_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FormatStorageResponse::_InternalParse( +const char* GetVideoStreamInfoResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8717,9 +9757,9 @@ const char* FormatStorageResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FormatStorageResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GetVideoStreamInfoResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8728,37 +9768,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FormatStorageResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_FormatStorageResponse_default_instance_._instance, + &_GetVideoStreamInfoResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; + // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.video_stream_info_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; + {PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.video_stream_info_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::VideoStreamInfo>()}, }}, {{ }}, }; -::uint8_t* FormatStorageResponse::_InternalSerialize( +::uint8_t* GetVideoStreamInfoResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetVideoStreamInfoResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.CameraResult camera_result = 1; + // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + 1, _Internal::video_stream_info(this), + _Internal::video_stream_info(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8766,157 +9806,124 @@ ::uint8_t* FormatStorageResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FormatStorageResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetVideoStreamInfoResponse) return target; } -::size_t FormatStorageResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FormatStorageResponse) +::size_t GetVideoStreamInfoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetVideoStreamInfoResponse) ::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; + // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.video_stream_info_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FormatStorageResponse::_class_data_ = { - FormatStorageResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetVideoStreamInfoResponse::_class_data_ = { + GetVideoStreamInfoResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FormatStorageResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetVideoStreamInfoResponse::GetClassData() const { return &_class_data_; } -void FormatStorageResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FormatStorageResponse) +void GetVideoStreamInfoResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetVideoStreamInfoResponse) 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_mutable_video_stream_info()->::mavsdk::rpc::camera::VideoStreamInfo::MergeFrom( + from._internal_video_stream_info()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void FormatStorageResponse::CopyFrom(const FormatStorageResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FormatStorageResponse) +void GetVideoStreamInfoResponse::CopyFrom(const GetVideoStreamInfoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetVideoStreamInfoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FormatStorageResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetVideoStreamInfoResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* FormatStorageResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetVideoStreamInfoResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void FormatStorageResponse::InternalSwap(FormatStorageResponse* PROTOBUF_RESTRICT other) { +void GetVideoStreamInfoResponse::InternalSwap(GetVideoStreamInfoResponse* PROTOBUF_RESTRICT 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_); + swap(_impl_.video_stream_info_, other->_impl_.video_stream_info_); } -::google::protobuf::Metadata FormatStorageResponse::GetMetadata() const { +::google::protobuf::Metadata GetVideoStreamInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[39]); + file_level_metadata_camera_2fcamera_2eproto[38]); } // =================================================================== -class SelectCameraResponse::_Internal { +class GetStatusRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const SelectCameraResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::CameraResult& SelectCameraResponse::_Internal::camera_result(const SelectCameraResponse* msg) { - return *msg->_impl_.camera_result_; -} -SelectCameraResponse::SelectCameraResponse(::google::protobuf::Arena* arena) +GetStatusRequest::GetStatusRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SelectCameraResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetStatusRequest) } -inline PROTOBUF_NDEBUG_INLINE SelectCameraResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -SelectCameraResponse::SelectCameraResponse( - ::google::protobuf::Arena* arena, - const SelectCameraResponse& from) - : ::google::protobuf::Message(arena) { - SelectCameraResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SelectCameraResponse) +GetStatusRequest::GetStatusRequest( + ::google::protobuf::Arena* arena, const GetStatusRequest& from) + : GetStatusRequest(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SelectCameraResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetStatusRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SelectCameraResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetStatusRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + _impl_.camera_id_ = {}; } -SelectCameraResponse::~SelectCameraResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraResponse) +GetStatusRequest::~GetStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetStatusRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SelectCameraResponse::SharedDtor() { +inline void GetStatusRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SelectCameraResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.SelectCameraResponse) +PROTOBUF_NOINLINE void GetStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetStatusRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - 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(); + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SelectCameraResponse::_InternalParse( +const char* GetStatusRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8924,48 +9931,251 @@ const char* SelectCameraResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SelectCameraResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetStatusRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_SelectCameraResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GetStatusRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_.camera_result_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetStatusRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetStatusRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(GetStatusRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* GetStatusRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetStatusRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetStatusRequest) + return target; +} + +::size_t GetStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetStatusRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetStatusRequest::_class_data_ = { + GetStatusRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetStatusRequest::GetClassData() const { + return &_class_data_; +} + +void GetStatusRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetStatusRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetStatusRequest::CopyFrom(const GetStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetStatusRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetStatusRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetStatusRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetStatusRequest::InternalSwap(GetStatusRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::Metadata GetStatusRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[39]); +} +// =================================================================== + +class GetStatusResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::Status& status(const GetStatusResponse* msg); + static void set_has_status(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::Status& GetStatusResponse::_Internal::status(const GetStatusResponse* msg) { + return *msg->_impl_.status_; +} +GetStatusResponse::GetStatusResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetStatusResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetStatusResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GetStatusResponse::GetStatusResponse( + ::google::protobuf::Arena* arena, + const GetStatusResponse& from) + : ::google::protobuf::Message(arena) { + GetStatusResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.status_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::Status>(arena, *from._impl_.status_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetStatusResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetStatusResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetStatusResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.status_ = {}; +} +GetStatusResponse::~GetStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetStatusResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetStatusResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.status_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetStatusResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.status_ != nullptr); + _impl_.status_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetStatusResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GetStatusResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GetStatusResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GetStatusResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.Status status = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetStatusResponse, _impl_.status_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.Status status = 1; + {PROTOBUF_FIELD_OFFSET(GetStatusResponse, _impl_.status_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Status>()}, }}, {{ }}, }; -::uint8_t* SelectCameraResponse::_InternalSerialize( +::uint8_t* GetStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.SelectCameraResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.CameraResult camera_result = 1; + // .mavsdk.rpc.camera.Status status = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + 1, _Internal::status(this), + _Internal::status(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8973,114 +10183,114 @@ ::uint8_t* SelectCameraResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.SelectCameraResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetStatusResponse) return target; } -::size_t SelectCameraResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraResponse) +::size_t GetStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetStatusResponse) ::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; + // .mavsdk.rpc.camera.Status status = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.status_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SelectCameraResponse::_class_data_ = { - SelectCameraResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetStatusResponse::_class_data_ = { + GetStatusResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SelectCameraResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetStatusResponse::GetClassData() const { return &_class_data_; } -void SelectCameraResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.SelectCameraResponse) +void GetStatusResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetStatusResponse) 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_mutable_status()->::mavsdk::rpc::camera::Status::MergeFrom( + from._internal_status()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SelectCameraResponse::CopyFrom(const SelectCameraResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.SelectCameraResponse) +void GetStatusResponse::CopyFrom(const GetStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SelectCameraResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetStatusResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SelectCameraResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetStatusResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SelectCameraResponse::InternalSwap(SelectCameraResponse* PROTOBUF_RESTRICT other) { +void GetStatusResponse::InternalSwap(GetStatusResponse* PROTOBUF_RESTRICT 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_); + swap(_impl_.status_, other->_impl_.status_); } -::google::protobuf::Metadata SelectCameraResponse::GetMetadata() const { +::google::protobuf::Metadata GetStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, file_level_metadata_camera_2fcamera_2eproto[40]); } // =================================================================== -class SelectCameraRequest::_Internal { +class GetCurrentSettingsRequest::_Internal { public: }; -SelectCameraRequest::SelectCameraRequest(::google::protobuf::Arena* arena) +GetCurrentSettingsRequest::GetCurrentSettingsRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SelectCameraRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetCurrentSettingsRequest) } -SelectCameraRequest::SelectCameraRequest( - ::google::protobuf::Arena* arena, const SelectCameraRequest& from) - : SelectCameraRequest(arena) { +GetCurrentSettingsRequest::GetCurrentSettingsRequest( + ::google::protobuf::Arena* arena, const GetCurrentSettingsRequest& from) + : GetCurrentSettingsRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SelectCameraRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetCurrentSettingsRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SelectCameraRequest::SharedCtor(::_pb::Arena* arena) { +inline void GetCurrentSettingsRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_id_ = {}; } -SelectCameraRequest::~SelectCameraRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraRequest) +GetCurrentSettingsRequest::~GetCurrentSettingsRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetCurrentSettingsRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SelectCameraRequest::SharedDtor() { +inline void GetCurrentSettingsRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SelectCameraRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.SelectCameraRequest) +PROTOBUF_NOINLINE void GetCurrentSettingsRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetCurrentSettingsRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9090,7 +10300,7 @@ PROTOBUF_NOINLINE void SelectCameraRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SelectCameraRequest::_InternalParse( +const char* GetCurrentSettingsRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9098,7 +10308,7 @@ const char* SelectCameraRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SelectCameraRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetCurrentSettingsRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -9109,17 +10319,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SelectCameraRequest::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SelectCameraRequest_default_instance_._instance, + &_GetCurrentSettingsRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // int32 camera_id = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SelectCameraRequest, _impl_.camera_id_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(SelectCameraRequest, _impl_.camera_id_)}}, + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetCurrentSettingsRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetCurrentSettingsRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ // int32 camera_id = 1; - {PROTOBUF_FIELD_OFFSET(SelectCameraRequest, _impl_.camera_id_), 0, 0, + {PROTOBUF_FIELD_OFFSET(GetCurrentSettingsRequest, _impl_.camera_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, // no aux_entries @@ -9127,10 +10337,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SelectCameraRequest::_table_ = { }}, }; -::uint8_t* SelectCameraRequest::_InternalSerialize( +::uint8_t* GetCurrentSettingsRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.SelectCameraRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetCurrentSettingsRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9146,12 +10356,12 @@ ::uint8_t* SelectCameraRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.SelectCameraRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetCurrentSettingsRequest) return target; } -::size_t SelectCameraRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraRequest) +::size_t GetCurrentSettingsRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetCurrentSettingsRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9167,18 +10377,18 @@ ::size_t SelectCameraRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SelectCameraRequest::_class_data_ = { - SelectCameraRequest::MergeImpl, +const ::google::protobuf::Message::ClassData GetCurrentSettingsRequest::_class_data_ = { + GetCurrentSettingsRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SelectCameraRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetCurrentSettingsRequest::GetClassData() const { return &_class_data_; } -void SelectCameraRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.SelectCameraRequest) +void GetCurrentSettingsRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetCurrentSettingsRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9189,98 +10399,64 @@ void SelectCameraRequest::MergeImpl(::google::protobuf::Message& to_msg, const : _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SelectCameraRequest::CopyFrom(const SelectCameraRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.SelectCameraRequest) +void GetCurrentSettingsRequest::CopyFrom(const GetCurrentSettingsRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetCurrentSettingsRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SelectCameraRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool GetCurrentSettingsRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SelectCameraRequest::AccessCachedSize() const { +::_pbi::CachedSize* GetCurrentSettingsRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SelectCameraRequest::InternalSwap(SelectCameraRequest* PROTOBUF_RESTRICT other) { +void GetCurrentSettingsRequest::InternalSwap(GetCurrentSettingsRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.camera_id_, other->_impl_.camera_id_); } -::google::protobuf::Metadata SelectCameraRequest::GetMetadata() const { +::google::protobuf::Metadata GetCurrentSettingsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, file_level_metadata_camera_2fcamera_2eproto[41]); } // =================================================================== -class ResetSettingsRequest::_Internal { - public: -}; - -ResetSettingsRequest::ResetSettingsRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsRequest) -} -ResetSettingsRequest::ResetSettingsRequest( - ::google::protobuf::Arena* arena, - const ResetSettingsRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - ResetSettingsRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ResetSettingsRequest) -} - - - - - - - - - -::google::protobuf::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 { +class GetCurrentSettingsResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ResetSettingsResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const GetCurrentSettingsResponse* 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) { +const ::mavsdk::rpc::camera::CameraResult& GetCurrentSettingsResponse::_Internal::camera_result(const GetCurrentSettingsResponse* msg) { return *msg->_impl_.camera_result_; } -ResetSettingsResponse::ResetSettingsResponse(::google::protobuf::Arena* arena) +GetCurrentSettingsResponse::GetCurrentSettingsResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetCurrentSettingsResponse) } -inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetCurrentSettingsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, - _cached_size_{0} {} + _cached_size_{0}, + current_settings_{visibility, arena, from.current_settings_} {} -ResetSettingsResponse::ResetSettingsResponse( +GetCurrentSettingsResponse::GetCurrentSettingsResponse( ::google::protobuf::Arena* arena, - const ResetSettingsResponse& from) + const GetCurrentSettingsResponse& from) : ::google::protobuf::Message(arena) { - ResetSettingsResponse* const _this = this; + GetCurrentSettingsResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9290,35 +10466,37 @@ ResetSettingsResponse::ResetSettingsResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ResetSettingsResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetCurrentSettingsResponse) } -inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetCurrentSettingsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : _cached_size_{0}, + current_settings_{visibility, arena} {} -inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetCurrentSettingsResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -ResetSettingsResponse::~ResetSettingsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ResetSettingsResponse) +GetCurrentSettingsResponse::~GetCurrentSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetCurrentSettingsResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ResetSettingsResponse::SharedDtor() { +inline void GetCurrentSettingsResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ResetSettingsResponse) +PROTOBUF_NOINLINE void GetCurrentSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetCurrentSettingsResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + _impl_.current_settings_.Clear(); cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { ABSL_DCHECK(_impl_.camera_result_ != nullptr); @@ -9328,7 +10506,7 @@ PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ResetSettingsResponse::_InternalParse( +const char* GetCurrentSettingsResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9336,39 +10514,46 @@ const char* ResetSettingsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ResetSettingsResponse::_table_ = { +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetCurrentSettingsResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_._has_bits_), 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries - 1, // num_aux_entries + 2, // num_field_entries + 2, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ResetSettingsResponse_default_instance_._instance, + &_GetCurrentSettingsResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ + // repeated .mavsdk.rpc.camera.Setting current_settings = 2; + {::_pbi::TcParser::FastMtR1, + {18, 63, 1, PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_.current_settings_)}}, // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.camera.Setting current_settings = 2; + {PROTOBUF_FIELD_OFFSET(GetCurrentSettingsResponse, _impl_.current_settings_), -1, 1, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, }}, {{ }}, }; -::uint8_t* ResetSettingsResponse::_InternalSerialize( +::uint8_t* GetCurrentSettingsResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetCurrentSettingsResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9380,23 +10565,37 @@ ::uint8_t* ResetSettingsResponse::_InternalSerialize( _Internal::camera_result(this).GetCachedSize(), target, stream); } + // repeated .mavsdk.rpc.camera.Setting current_settings = 2; + for (unsigned i = 0, + n = static_cast(this->_internal_current_settings_size()); i < n; i++) { + const auto& repfield = this->_internal_current_settings().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(2, repfield, repfield.GetCachedSize(), target, stream); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetCurrentSettingsResponse) return target; } -::size_t ResetSettingsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ResetSettingsResponse) +::size_t GetCurrentSettingsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetCurrentSettingsResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + // repeated .mavsdk.rpc.camera.Setting current_settings = 2; + total_size += 1UL * this->_internal_current_settings_size(); + for (const auto& msg : this->_internal_current_settings()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } // .mavsdk.rpc.camera.CameraResult camera_result = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { @@ -9407,22 +10606,24 @@ ::size_t ResetSettingsResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ResetSettingsResponse::_class_data_ = { - ResetSettingsResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetCurrentSettingsResponse::_class_data_ = { + GetCurrentSettingsResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ResetSettingsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetCurrentSettingsResponse::GetClassData() const { return &_class_data_; } -void ResetSettingsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ResetSettingsResponse) +void GetCurrentSettingsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetCurrentSettingsResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + _this->_internal_mutable_current_settings()->MergeFrom( + from._internal_current_settings()); if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( from._internal_camera_result()); @@ -9430,147 +10631,80 @@ void ResetSettingsResponse::MergeImpl(::google::protobuf::Message& to_msg, const _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ResetSettingsResponse::CopyFrom(const ResetSettingsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ResetSettingsResponse) +void GetCurrentSettingsResponse::CopyFrom(const GetCurrentSettingsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetCurrentSettingsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ResetSettingsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetCurrentSettingsResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ResetSettingsResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetCurrentSettingsResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* PROTOBUF_RESTRICT other) { +void GetCurrentSettingsResponse::InternalSwap(GetCurrentSettingsResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + _impl_.current_settings_.InternalSwap(&other->_impl_.current_settings_); swap(_impl_.camera_result_, other->_impl_.camera_result_); } -::google::protobuf::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 ZoomInStartRequest::_Internal { - public: -}; - -ZoomInStartRequest::ZoomInStartRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomInStartRequest) -} -ZoomInStartRequest::ZoomInStartRequest( - ::google::protobuf::Arena* arena, - const ZoomInStartRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - ZoomInStartRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomInStartRequest) -} - - - - - - - - - -::google::protobuf::Metadata ZoomInStartRequest::GetMetadata() const { +::google::protobuf::Metadata GetCurrentSettingsResponse::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[42]); } // =================================================================== -class ZoomInStartResponse::_Internal { +class GetPossibleSettingOptionsRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomInStartResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::CameraResult& ZoomInStartResponse::_Internal::camera_result(const ZoomInStartResponse* msg) { - return *msg->_impl_.camera_result_; -} -ZoomInStartResponse::ZoomInStartResponse(::google::protobuf::Arena* arena) +GetPossibleSettingOptionsRequest::GetPossibleSettingOptionsRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomInStartResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) } -inline PROTOBUF_NDEBUG_INLINE ZoomInStartResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -ZoomInStartResponse::ZoomInStartResponse( - ::google::protobuf::Arena* arena, - const ZoomInStartResponse& from) - : ::google::protobuf::Message(arena) { - ZoomInStartResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomInStartResponse) +GetPossibleSettingOptionsRequest::GetPossibleSettingOptionsRequest( + ::google::protobuf::Arena* arena, const GetPossibleSettingOptionsRequest& from) + : GetPossibleSettingOptionsRequest(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE ZoomInStartResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetPossibleSettingOptionsRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ZoomInStartResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetPossibleSettingOptionsRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + _impl_.camera_id_ = {}; } -ZoomInStartResponse::~ZoomInStartResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomInStartResponse) +GetPossibleSettingOptionsRequest::~GetPossibleSettingOptionsRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ZoomInStartResponse::SharedDtor() { +inline void GetPossibleSettingOptionsRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ZoomInStartResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomInStartResponse) +PROTOBUF_NOINLINE void GetPossibleSettingOptionsRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - 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(); + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ZoomInStartResponse::_InternalParse( +const char* GetPossibleSettingOptionsRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9578,48 +10712,47 @@ const char* ZoomInStartResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomInStartResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetPossibleSettingOptionsRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_ZoomInStartResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GetPossibleSettingOptionsRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.camera_result_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetPossibleSettingOptionsRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, - }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* ZoomInStartResponse::_InternalSerialize( +::uint8_t* GetPossibleSettingOptionsRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomInStartResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) ::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 = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9627,144 +10760,107 @@ ::uint8_t* ZoomInStartResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomInStartResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) return target; } -::size_t ZoomInStartResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomInStartResponse) +::size_t GetPossibleSettingOptionsRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ZoomInStartResponse::_class_data_ = { - ZoomInStartResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetPossibleSettingOptionsRequest::_class_data_ = { + GetPossibleSettingOptionsRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ZoomInStartResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetPossibleSettingOptionsRequest::GetClassData() const { return &_class_data_; } -void ZoomInStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomInStartResponse) +void GetPossibleSettingOptionsRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) 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()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ZoomInStartResponse::CopyFrom(const ZoomInStartResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomInStartResponse) +void GetPossibleSettingOptionsRequest::CopyFrom(const GetPossibleSettingOptionsRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetPossibleSettingOptionsRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ZoomInStartResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetPossibleSettingOptionsRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* ZoomInStartResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetPossibleSettingOptionsRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void ZoomInStartResponse::InternalSwap(ZoomInStartResponse* PROTOBUF_RESTRICT other) { +void GetPossibleSettingOptionsRequest::InternalSwap(GetPossibleSettingOptionsRequest* PROTOBUF_RESTRICT 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_); -} - -::google::protobuf::Metadata ZoomInStartResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[45]); -} -// =================================================================== - -class ZoomOutStartRequest::_Internal { - public: -}; - -ZoomOutStartRequest::ZoomOutStartRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomOutStartRequest) -} -ZoomOutStartRequest::ZoomOutStartRequest( - ::google::protobuf::Arena* arena, - const ZoomOutStartRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - ZoomOutStartRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomOutStartRequest) + swap(_impl_.camera_id_, other->_impl_.camera_id_); } - - - - - - - - -::google::protobuf::Metadata ZoomOutStartRequest::GetMetadata() const { +::google::protobuf::Metadata GetPossibleSettingOptionsRequest::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[43]); } // =================================================================== -class ZoomOutStartResponse::_Internal { +class GetPossibleSettingOptionsResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomOutStartResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const GetPossibleSettingOptionsResponse* msg); static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& ZoomOutStartResponse::_Internal::camera_result(const ZoomOutStartResponse* msg) { +const ::mavsdk::rpc::camera::CameraResult& GetPossibleSettingOptionsResponse::_Internal::camera_result(const GetPossibleSettingOptionsResponse* msg) { return *msg->_impl_.camera_result_; } -ZoomOutStartResponse::ZoomOutStartResponse(::google::protobuf::Arena* arena) +GetPossibleSettingOptionsResponse::GetPossibleSettingOptionsResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomOutStartResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) } -inline PROTOBUF_NDEBUG_INLINE ZoomOutStartResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetPossibleSettingOptionsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, - _cached_size_{0} {} + _cached_size_{0}, + setting_options_{visibility, arena, from.setting_options_} {} -ZoomOutStartResponse::ZoomOutStartResponse( +GetPossibleSettingOptionsResponse::GetPossibleSettingOptionsResponse( ::google::protobuf::Arena* arena, - const ZoomOutStartResponse& from) + const GetPossibleSettingOptionsResponse& from) : ::google::protobuf::Message(arena) { - ZoomOutStartResponse* const _this = this; + GetPossibleSettingOptionsResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9774,35 +10870,37 @@ ZoomOutStartResponse::ZoomOutStartResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomOutStartResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) } -inline PROTOBUF_NDEBUG_INLINE ZoomOutStartResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetPossibleSettingOptionsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : _cached_size_{0}, + setting_options_{visibility, arena} {} -inline void ZoomOutStartResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetPossibleSettingOptionsResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -ZoomOutStartResponse::~ZoomOutStartResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomOutStartResponse) +GetPossibleSettingOptionsResponse::~GetPossibleSettingOptionsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ZoomOutStartResponse::SharedDtor() { +inline void GetPossibleSettingOptionsResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ZoomOutStartResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomOutStartResponse) +PROTOBUF_NOINLINE void GetPossibleSettingOptionsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; + _impl_.setting_options_.Clear(); cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { ABSL_DCHECK(_impl_.camera_result_ != nullptr); @@ -9812,7 +10910,7 @@ PROTOBUF_NOINLINE void ZoomOutStartResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ZoomOutStartResponse::_InternalParse( +const char* GetPossibleSettingOptionsResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9820,39 +10918,46 @@ const char* ZoomOutStartResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomOutStartResponse::_table_ = { +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetPossibleSettingOptionsResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_._has_bits_), 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries - 1, // num_aux_entries + 2, // num_field_entries + 2, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ZoomOutStartResponse_default_instance_._instance, + &_GetPossibleSettingOptionsResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ + // repeated .mavsdk.rpc.camera.SettingOptions setting_options = 2; + {::_pbi::TcParser::FastMtR1, + {18, 63, 1, PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_.setting_options_)}}, // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.camera.SettingOptions setting_options = 2; + {PROTOBUF_FIELD_OFFSET(GetPossibleSettingOptionsResponse, _impl_.setting_options_), -1, 1, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::SettingOptions>()}, }}, {{ }}, }; -::uint8_t* ZoomOutStartResponse::_InternalSerialize( +::uint8_t* GetPossibleSettingOptionsResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomOutStartResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9864,25 +10969,39 @@ ::uint8_t* ZoomOutStartResponse::_InternalSerialize( _Internal::camera_result(this).GetCachedSize(), target, stream); } + // repeated .mavsdk.rpc.camera.SettingOptions setting_options = 2; + for (unsigned i = 0, + n = static_cast(this->_internal_setting_options_size()); i < n; i++) { + const auto& repfield = this->_internal_setting_options().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(2, repfield, repfield.GetCachedSize(), target, stream); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomOutStartResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) return target; } -::size_t ZoomOutStartResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomOutStartResponse) +::size_t GetPossibleSettingOptionsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) ::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]; + // repeated .mavsdk.rpc.camera.SettingOptions setting_options = 2; + total_size += 1UL * this->_internal_setting_options_size(); + for (const auto& msg : this->_internal_setting_options()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); @@ -9891,22 +11010,24 @@ ::size_t ZoomOutStartResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ZoomOutStartResponse::_class_data_ = { - ZoomOutStartResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetPossibleSettingOptionsResponse::_class_data_ = { + GetPossibleSettingOptionsResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ZoomOutStartResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetPossibleSettingOptionsResponse::GetClassData() const { return &_class_data_; } -void ZoomOutStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomOutStartResponse) +void GetPossibleSettingOptionsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + _this->_internal_mutable_setting_options()->MergeFrom( + from._internal_setting_options()); if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( from._internal_camera_result()); @@ -9914,132 +11035,104 @@ void ZoomOutStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ZoomOutStartResponse::CopyFrom(const ZoomOutStartResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomOutStartResponse) +void GetPossibleSettingOptionsResponse::CopyFrom(const GetPossibleSettingOptionsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetPossibleSettingOptionsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ZoomOutStartResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetPossibleSettingOptionsResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ZoomOutStartResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetPossibleSettingOptionsResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ZoomOutStartResponse::InternalSwap(ZoomOutStartResponse* PROTOBUF_RESTRICT other) { +void GetPossibleSettingOptionsResponse::InternalSwap(GetPossibleSettingOptionsResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + _impl_.setting_options_.InternalSwap(&other->_impl_.setting_options_); swap(_impl_.camera_result_, other->_impl_.camera_result_); } -::google::protobuf::Metadata ZoomOutStartResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[47]); -} -// =================================================================== - -class ZoomStopRequest::_Internal { - public: -}; - -ZoomStopRequest::ZoomStopRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomStopRequest) -} -ZoomStopRequest::ZoomStopRequest( - ::google::protobuf::Arena* arena, - const ZoomStopRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - ZoomStopRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomStopRequest) -} - - - - - - - - - -::google::protobuf::Metadata ZoomStopRequest::GetMetadata() const { +::google::protobuf::Metadata GetPossibleSettingOptionsResponse::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[44]); } // =================================================================== -class ZoomStopResponse::_Internal { +class GetSettingRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomStopResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::Setting& setting(const GetSettingRequest* msg); + static void set_has_setting(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& ZoomStopResponse::_Internal::camera_result(const ZoomStopResponse* msg) { - return *msg->_impl_.camera_result_; +const ::mavsdk::rpc::camera::Setting& GetSettingRequest::_Internal::setting(const GetSettingRequest* msg) { + return *msg->_impl_.setting_; } -ZoomStopResponse::ZoomStopResponse(::google::protobuf::Arena* arena) +GetSettingRequest::GetSettingRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomStopResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetSettingRequest) } -inline PROTOBUF_NDEBUG_INLINE ZoomStopResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetSettingRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ZoomStopResponse::ZoomStopResponse( +GetSettingRequest::GetSettingRequest( ::google::protobuf::Arena* arena, - const ZoomStopResponse& from) + const GetSettingRequest& from) : ::google::protobuf::Message(arena) { - ZoomStopResponse* const _this = this; + GetSettingRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + _impl_.setting_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::Setting>(arena, *from._impl_.setting_) : nullptr; + _impl_.camera_id_ = from._impl_.camera_id_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomStopResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetSettingRequest) } -inline PROTOBUF_NDEBUG_INLINE ZoomStopResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetSettingRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ZoomStopResponse::SharedCtor(::_pb::Arena* arena) { +inline void GetSettingRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, setting_), + 0, + offsetof(Impl_, camera_id_) - + offsetof(Impl_, setting_) + + sizeof(Impl_::camera_id_)); } -ZoomStopResponse::~ZoomStopResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomStopResponse) +GetSettingRequest::~GetSettingRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetSettingRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ZoomStopResponse::SharedDtor() { +inline void GetSettingRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; + delete _impl_.setting_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ZoomStopResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomStopResponse) +PROTOBUF_NOINLINE void GetSettingRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetSettingRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10047,14 +11140,15 @@ PROTOBUF_NOINLINE void ZoomStopResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_result_ != nullptr); - _impl_.camera_result_->Clear(); + ABSL_DCHECK(_impl_.setting_ != nullptr); + _impl_.setting_->Clear(); } + _impl_.camera_id_ = 0; _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ZoomStopResponse::_InternalParse( +const char* GetSettingRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10062,48 +11156,61 @@ const char* ZoomStopResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomStopResponse::_table_ = { +const ::_pbi::TcParseTable<1, 2, 1, 0, 2> GetSettingRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_._has_bits_), 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ZoomStopResponse_default_instance_._instance, + &_GetSettingRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; + // .mavsdk.rpc.camera.Setting setting = 2; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.camera_result_)}}, + {18, 0, 0, PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.setting_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetSettingRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.camera_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.Setting setting = 2; + {PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.setting_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, }}, {{ }}, }; -::uint8_t* ZoomStopResponse::_InternalSerialize( +::uint8_t* GetSettingRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomStopResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetSettingRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.CameraResult camera_result = 1; + // .mavsdk.rpc.camera.Setting setting = 2; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + 2, _Internal::setting(this), + _Internal::setting(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10111,124 +11218,2752 @@ ::uint8_t* ZoomStopResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomStopResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetSettingRequest) return target; } -::size_t ZoomStopResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomStopResponse) +::size_t GetSettingRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetSettingRequest) ::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; + // .mavsdk.rpc.camera.Setting setting = 2; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.setting_); + } + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ZoomStopResponse::_class_data_ = { - ZoomStopResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GetSettingRequest::_class_data_ = { + GetSettingRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ZoomStopResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetSettingRequest::GetClassData() const { return &_class_data_; } -void ZoomStopResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomStopResponse) +void GetSettingRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetSettingRequest) 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_mutable_setting()->::mavsdk::rpc::camera::Setting::MergeFrom( + from._internal_setting()); + } + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ZoomStopResponse::CopyFrom(const ZoomStopResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomStopResponse) +void GetSettingRequest::CopyFrom(const GetSettingRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetSettingRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ZoomStopResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GetSettingRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* ZoomStopResponse::AccessCachedSize() const { +::_pbi::CachedSize* GetSettingRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void ZoomStopResponse::InternalSwap(ZoomStopResponse* PROTOBUF_RESTRICT other) { +void GetSettingRequest::InternalSwap(GetSettingRequest* PROTOBUF_RESTRICT 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_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.camera_id_) + + sizeof(GetSettingRequest::_impl_.camera_id_) + - PROTOBUF_FIELD_OFFSET(GetSettingRequest, _impl_.setting_)>( + reinterpret_cast(&_impl_.setting_), + reinterpret_cast(&other->_impl_.setting_)); } -::google::protobuf::Metadata ZoomStopResponse::GetMetadata() const { +::google::protobuf::Metadata GetSettingRequest::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[45]); } // =================================================================== -class ZoomRangeRequest::_Internal { +class GetSettingResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const GetSettingResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::camera::Setting& setting(const GetSettingResponse* msg); + static void set_has_setting(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } }; -ZoomRangeRequest::ZoomRangeRequest(::google::protobuf::Arena* arena) +const ::mavsdk::rpc::camera::CameraResult& GetSettingResponse::_Internal::camera_result(const GetSettingResponse* msg) { + return *msg->_impl_.camera_result_; +} +const ::mavsdk::rpc::camera::Setting& GetSettingResponse::_Internal::setting(const GetSettingResponse* msg) { + return *msg->_impl_.setting_; +} +GetSettingResponse::GetSettingResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomRangeRequest) -} -ZoomRangeRequest::ZoomRangeRequest( - ::google::protobuf::Arena* arena, const ZoomRangeRequest& from) - : ZoomRangeRequest(arena) { - MergeFrom(from); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.GetSettingResponse) } -inline PROTOBUF_NDEBUG_INLINE ZoomRangeRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} +inline PROTOBUF_NDEBUG_INLINE GetSettingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} -inline void ZoomRangeRequest::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.range_ = {}; -} -ZoomRangeRequest::~ZoomRangeRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomRangeRequest) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ZoomRangeRequest::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.~Impl_(); +GetSettingResponse::GetSettingResponse( + ::google::protobuf::Arena* arena, + const GetSettingResponse& from) + : ::google::protobuf::Message(arena) { + GetSettingResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + _impl_.setting_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::Setting>(arena, *from._impl_.setting_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.GetSettingResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetSettingResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetSettingResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_result_), + 0, + offsetof(Impl_, setting_) - + offsetof(Impl_, camera_result_) + + sizeof(Impl_::setting_)); +} +GetSettingResponse::~GetSettingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.GetSettingResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetSettingResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + delete _impl_.setting_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetSettingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.GetSettingResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.camera_result_ != nullptr); + _impl_.camera_result_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.setting_ != nullptr); + _impl_.setting_->Clear(); + } + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetSettingResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetSettingResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_._has_bits_), + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 2, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GetSettingResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.Setting setting = 2; + {::_pbi::TcParser::FastMtS1, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_)}}, + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.camera.Setting setting = 2; + {PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Setting>()}, + }}, {{ + }}, +}; + +::uint8_t* GetSettingResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.GetSettingResponse) + ::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 = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::camera_result(this), + _Internal::camera_result(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.camera.Setting setting = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::setting(this), + _Internal::setting(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.GetSettingResponse) + return target; +} + +::size_t GetSettingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.GetSettingResponse) + ::size_t total_size = 0; + + ::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 & 0x00000003u) { + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + // .mavsdk.rpc.camera.Setting setting = 2; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.setting_); + } + + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetSettingResponse::_class_data_ = { + GetSettingResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetSettingResponse::GetClassData() const { + return &_class_data_; +} + +void GetSettingResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.GetSettingResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( + from._internal_camera_result()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_setting()->::mavsdk::rpc::camera::Setting::MergeFrom( + from._internal_setting()); + } + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetSettingResponse::CopyFrom(const GetSettingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.GetSettingResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetSettingResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetSettingResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetSettingResponse::InternalSwap(GetSettingResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.setting_) + + sizeof(GetSettingResponse::_impl_.setting_) + - PROTOBUF_FIELD_OFFSET(GetSettingResponse, _impl_.camera_result_)>( + reinterpret_cast(&_impl_.camera_result_), + reinterpret_cast(&other->_impl_.camera_result_)); +} + +::google::protobuf::Metadata GetSettingResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[46]); +} +// =================================================================== + +class FormatStorageRequest::_Internal { + public: +}; + +FormatStorageRequest::FormatStorageRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FormatStorageRequest) +} +FormatStorageRequest::FormatStorageRequest( + ::google::protobuf::Arena* arena, const FormatStorageRequest& from) + : FormatStorageRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE FormatStorageRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FormatStorageRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, storage_id_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::storage_id_)); +} +FormatStorageRequest::~FormatStorageRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FormatStorageRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FormatStorageRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void FormatStorageRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FormatStorageRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.storage_id_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.storage_id_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* FormatStorageRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> FormatStorageRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_FormatStorageRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 storage_id = 2; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FormatStorageRequest, _impl_.storage_id_), 63>(), + {16, 63, 0, PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.storage_id_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FormatStorageRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // int32 storage_id = 2; + {PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.storage_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* FormatStorageRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // int32 storage_id = 2; + if (this->_internal_storage_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<2>( + stream, this->_internal_storage_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // int32 storage_id = 2; + if (this->_internal_storage_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_storage_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData FormatStorageRequest::_class_data_ = { + FormatStorageRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* FormatStorageRequest::GetClassData() const { + return &_class_data_; +} + +void FormatStorageRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FormatStorageRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + if (from._internal_storage_id() != 0) { + _this->_internal_set_storage_id(from._internal_storage_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::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); +} + +PROTOBUF_NOINLINE bool FormatStorageRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* FormatStorageRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void FormatStorageRequest::InternalSwap(FormatStorageRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.storage_id_) + + sizeof(FormatStorageRequest::_impl_.storage_id_) + - PROTOBUF_FIELD_OFFSET(FormatStorageRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); +} + +::google::protobuf::Metadata FormatStorageRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[47]); +} +// =================================================================== + +class FormatStorageResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FormatStorageResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& FormatStorageResponse::_Internal::camera_result(const FormatStorageResponse* msg) { + return *msg->_impl_.camera_result_; +} +FormatStorageResponse::FormatStorageResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FormatStorageResponse) +} +inline PROTOBUF_NDEBUG_INLINE FormatStorageResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +FormatStorageResponse::FormatStorageResponse( + ::google::protobuf::Arena* arena, + const FormatStorageResponse& from) + : ::google::protobuf::Message(arena) { + FormatStorageResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FormatStorageResponse) +} +inline PROTOBUF_NDEBUG_INLINE FormatStorageResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FormatStorageResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +FormatStorageResponse::~FormatStorageResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FormatStorageResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FormatStorageResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void FormatStorageResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FormatStorageResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* FormatStorageResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FormatStorageResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_FormatStorageResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* FormatStorageResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FormatStorageResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FormatStorageResponse) + return target; +} + +::size_t FormatStorageResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FormatStorageResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData FormatStorageResponse::_class_data_ = { + FormatStorageResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* FormatStorageResponse::GetClassData() const { + return &_class_data_; +} + +void FormatStorageResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FormatStorageResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( + from._internal_camera_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void FormatStorageResponse::CopyFrom(const FormatStorageResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FormatStorageResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool FormatStorageResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* FormatStorageResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void FormatStorageResponse::InternalSwap(FormatStorageResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata FormatStorageResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[48]); +} +// =================================================================== + +class ResetSettingsRequest::_Internal { + public: +}; + +ResetSettingsRequest::ResetSettingsRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsRequest) +} +ResetSettingsRequest::ResetSettingsRequest( + ::google::protobuf::Arena* arena, const ResetSettingsRequest& from) + : ResetSettingsRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ResetSettingsRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ResetSettingsRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +ResetSettingsRequest::~ResetSettingsRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ResetSettingsRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ResetSettingsRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ResetSettingsRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ResetSettingsRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ResetSettingsRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ResetSettingsRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ResetSettingsRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ResetSettingsRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ResetSettingsRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ResetSettingsRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ResetSettingsRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ResetSettingsRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ResetSettingsRequest) + return target; +} + +::size_t ResetSettingsRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ResetSettingsRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ResetSettingsRequest::_class_data_ = { + ResetSettingsRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ResetSettingsRequest::GetClassData() const { + return &_class_data_; +} + +void ResetSettingsRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ResetSettingsRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ResetSettingsRequest::CopyFrom(const ResetSettingsRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ResetSettingsRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ResetSettingsRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ResetSettingsRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ResetSettingsRequest::InternalSwap(ResetSettingsRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::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[49]); +} +// =================================================================== + +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(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ResetSettingsResponse) +} +inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ResetSettingsResponse::ResetSettingsResponse( + ::google::protobuf::Arena* arena, + const ResetSettingsResponse& from) + : ::google::protobuf::Message(arena) { + ResetSettingsResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ResetSettingsResponse) +} +inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +ResetSettingsResponse::~ResetSettingsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ResetSettingsResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ResetSettingsResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ResetSettingsResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* ResetSettingsResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ResetSettingsResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ResetSettingsResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* ResetSettingsResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ResetSettingsResponse::_class_data_ = { + ResetSettingsResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ResetSettingsResponse::GetClassData() const { + return &_class_data_; +} + +void ResetSettingsResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.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<::google::protobuf::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); +} + +PROTOBUF_NOINLINE bool ResetSettingsResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ResetSettingsResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::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[50]); +} +// =================================================================== + +class ZoomInStartRequest::_Internal { + public: +}; + +ZoomInStartRequest::ZoomInStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomInStartRequest) +} +ZoomInStartRequest::ZoomInStartRequest( + ::google::protobuf::Arena* arena, const ZoomInStartRequest& from) + : ZoomInStartRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomInStartRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomInStartRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +ZoomInStartRequest::~ZoomInStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomInStartRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomInStartRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomInStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomInStartRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomInStartRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomInStartRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomInStartRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomInStartRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomInStartRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ZoomInStartRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomInStartRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomInStartRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomInStartRequest) + return target; +} + +::size_t ZoomInStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomInStartRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomInStartRequest::_class_data_ = { + ZoomInStartRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomInStartRequest::GetClassData() const { + return &_class_data_; +} + +void ZoomInStartRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomInStartRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomInStartRequest::CopyFrom(const ZoomInStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomInStartRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomInStartRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomInStartRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomInStartRequest::InternalSwap(ZoomInStartRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::Metadata ZoomInStartRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[51]); +} +// =================================================================== + +class ZoomInStartResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomInStartResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& ZoomInStartResponse::_Internal::camera_result(const ZoomInStartResponse* msg) { + return *msg->_impl_.camera_result_; +} +ZoomInStartResponse::ZoomInStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomInStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ZoomInStartResponse::ZoomInStartResponse( + ::google::protobuf::Arena* arena, + const ZoomInStartResponse& from) + : ::google::protobuf::Message(arena) { + ZoomInStartResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomInStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomInStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +ZoomInStartResponse::~ZoomInStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomInStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomInStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomInStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomInStartResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomInStartResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomInStartResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ZoomInStartResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(ZoomInStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* ZoomInStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomInStartResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomInStartResponse) + return target; +} + +::size_t ZoomInStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomInStartResponse) + ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomInStartResponse::_class_data_ = { + ZoomInStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomInStartResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomInStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomInStartResponse) + 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<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomInStartResponse::CopyFrom(const ZoomInStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomInStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomInStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomInStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomInStartResponse::InternalSwap(ZoomInStartResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata ZoomInStartResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[52]); +} +// =================================================================== + +class ZoomOutStartRequest::_Internal { + public: +}; + +ZoomOutStartRequest::ZoomOutStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomOutStartRequest) +} +ZoomOutStartRequest::ZoomOutStartRequest( + ::google::protobuf::Arena* arena, const ZoomOutStartRequest& from) + : ZoomOutStartRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomOutStartRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomOutStartRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +ZoomOutStartRequest::~ZoomOutStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomOutStartRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomOutStartRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomOutStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomOutStartRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomOutStartRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomOutStartRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomOutStartRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomOutStartRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomOutStartRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ZoomOutStartRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomOutStartRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomOutStartRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomOutStartRequest) + return target; +} + +::size_t ZoomOutStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomOutStartRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomOutStartRequest::_class_data_ = { + ZoomOutStartRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomOutStartRequest::GetClassData() const { + return &_class_data_; +} + +void ZoomOutStartRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomOutStartRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomOutStartRequest::CopyFrom(const ZoomOutStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomOutStartRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomOutStartRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomOutStartRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomOutStartRequest::InternalSwap(ZoomOutStartRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::Metadata ZoomOutStartRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[53]); +} +// =================================================================== + +class ZoomOutStartResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomOutStartResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& ZoomOutStartResponse::_Internal::camera_result(const ZoomOutStartResponse* msg) { + return *msg->_impl_.camera_result_; +} +ZoomOutStartResponse::ZoomOutStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ZoomOutStartResponse::ZoomOutStartResponse( + ::google::protobuf::Arena* arena, + const ZoomOutStartResponse& from) + : ::google::protobuf::Message(arena) { + ZoomOutStartResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomOutStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +ZoomOutStartResponse::~ZoomOutStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomOutStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomOutStartResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomOutStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomOutStartResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomOutStartResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomOutStartResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ZoomOutStartResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(ZoomOutStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* ZoomOutStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomOutStartResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomOutStartResponse) + return target; +} + +::size_t ZoomOutStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomOutStartResponse) + ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomOutStartResponse::_class_data_ = { + ZoomOutStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomOutStartResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomOutStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomOutStartResponse) + 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<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomOutStartResponse::CopyFrom(const ZoomOutStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomOutStartResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomOutStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomOutStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomOutStartResponse::InternalSwap(ZoomOutStartResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata ZoomOutStartResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[54]); +} +// =================================================================== + +class ZoomStopRequest::_Internal { + public: +}; + +ZoomStopRequest::ZoomStopRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomStopRequest) +} +ZoomStopRequest::ZoomStopRequest( + ::google::protobuf::Arena* arena, const ZoomStopRequest& from) + : ZoomStopRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomStopRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomStopRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +ZoomStopRequest::~ZoomStopRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomStopRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomStopRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomStopRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomStopRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomStopRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomStopRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomStopRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomStopRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomStopRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ZoomStopRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomStopRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomStopRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomStopRequest) + return target; +} + +::size_t ZoomStopRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomStopRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomStopRequest::_class_data_ = { + ZoomStopRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomStopRequest::GetClassData() const { + return &_class_data_; +} + +void ZoomStopRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomStopRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomStopRequest::CopyFrom(const ZoomStopRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomStopRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomStopRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomStopRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomStopRequest::InternalSwap(ZoomStopRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} + +::google::protobuf::Metadata ZoomStopRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[55]); +} +// =================================================================== + +class ZoomStopResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomStopResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& ZoomStopResponse::_Internal::camera_result(const ZoomStopResponse* msg) { + return *msg->_impl_.camera_result_; +} +ZoomStopResponse::ZoomStopResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomStopResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomStopResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ZoomStopResponse::ZoomStopResponse( + ::google::protobuf::Arena* arena, + const ZoomStopResponse& from) + : ::google::protobuf::Message(arena) { + ZoomStopResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomStopResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomStopResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomStopResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +ZoomStopResponse::~ZoomStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomStopResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomStopResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomStopResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomStopResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomStopResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomStopResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ZoomStopResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(ZoomStopResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* ZoomStopResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomStopResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomStopResponse) + return target; +} + +::size_t ZoomStopResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomStopResponse) + ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomStopResponse::_class_data_ = { + ZoomStopResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomStopResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomStopResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomStopResponse) + 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<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomStopResponse::CopyFrom(const ZoomStopResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomStopResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomStopResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomStopResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomStopResponse::InternalSwap(ZoomStopResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata ZoomStopResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[56]); +} +// =================================================================== + +class ZoomRangeRequest::_Internal { + public: +}; + +ZoomRangeRequest::ZoomRangeRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomRangeRequest) +} +ZoomRangeRequest::ZoomRangeRequest( + ::google::protobuf::Arena* arena, const ZoomRangeRequest& from) + : ZoomRangeRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ZoomRangeRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomRangeRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, range_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::range_)); +} +ZoomRangeRequest::~ZoomRangeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomRangeRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomRangeRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomRangeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomRangeRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.range_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.range_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomRangeRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> ZoomRangeRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ZoomRangeRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // float range = 2; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ZoomRangeRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float range = 2; + {PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ZoomRangeRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomRangeRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // float range = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_range = this->_internal_range(); + ::uint32_t raw_range; + memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); + if (raw_range != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_range(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomRangeRequest) + return target; +} + +::size_t ZoomRangeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomRangeRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // float range = 2; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_range = this->_internal_range(); + ::uint32_t raw_range; + memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); + if (raw_range != 0) { + total_size += 5; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomRangeRequest::_class_data_ = { + ZoomRangeRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomRangeRequest::GetClassData() const { + return &_class_data_; +} + +void ZoomRangeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomRangeRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_range = from._internal_range(); + ::uint32_t raw_range; + memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); + if (raw_range != 0) { + _this->_internal_set_range(from._internal_range()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomRangeRequest::CopyFrom(const ZoomRangeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomRangeRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomRangeRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomRangeRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomRangeRequest::InternalSwap(ZoomRangeRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_) + + sizeof(ZoomRangeRequest::_impl_.range_) + - PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); +} + +::google::protobuf::Metadata ZoomRangeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[57]); +} +// =================================================================== + +class ZoomRangeResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomRangeResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& ZoomRangeResponse::_Internal::camera_result(const ZoomRangeResponse* msg) { + return *msg->_impl_.camera_result_; +} +ZoomRangeResponse::ZoomRangeResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomRangeResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomRangeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ZoomRangeResponse::ZoomRangeResponse( + ::google::protobuf::Arena* arena, + const ZoomRangeResponse& from) + : ::google::protobuf::Message(arena) { + ZoomRangeResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomRangeResponse) +} +inline PROTOBUF_NDEBUG_INLINE ZoomRangeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ZoomRangeResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +ZoomRangeResponse::~ZoomRangeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomRangeResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ZoomRangeResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.camera_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ZoomRangeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomRangeResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + 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<::google::protobuf::UnknownFieldSet>(); +} + +const char* ZoomRangeResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomRangeResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ZoomRangeResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.camera_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* ZoomRangeResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomRangeResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomRangeResponse) + return target; +} + +::size_t ZoomRangeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomRangeResponse) + ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData ZoomRangeResponse::_class_data_ = { + ZoomRangeResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ZoomRangeResponse::GetClassData() const { + return &_class_data_; +} + +void ZoomRangeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomRangeResponse) + 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<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void ZoomRangeResponse::CopyFrom(const ZoomRangeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomRangeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool ZoomRangeResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* ZoomRangeResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ZoomRangeResponse::InternalSwap(ZoomRangeResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata ZoomRangeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[58]); +} +// =================================================================== + +class TrackPointRequest::_Internal { + public: +}; + +TrackPointRequest::TrackPointRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackPointRequest) } +TrackPointRequest::TrackPointRequest( + ::google::protobuf::Arena* arena, const TrackPointRequest& from) + : TrackPointRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE TrackPointRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} -PROTOBUF_NOINLINE void ZoomRangeRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomRangeRequest) +inline void TrackPointRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, radius_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::radius_)); +} +TrackPointRequest::~TrackPointRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackPointRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void TrackPointRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void TrackPointRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackPointRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.range_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.radius_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.radius_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ZoomRangeRequest::_InternalParse( +const char* TrackPointRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10236,28 +13971,46 @@ const char* ZoomRangeRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomRangeRequest::_table_ = { +const ::_pbi::TcParseTable<2, 4, 0, 0, 2> TrackPointRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 4, 24, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967280, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 4, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_ZoomRangeRequest_default_instance_._instance, + &_TrackPointRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // float range = 1; + // float radius = 4; + {::_pbi::TcParser::FastF32S1, + {37, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TrackPointRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.camera_id_)}}, + // float point_x = 2; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_)}}, + // float point_y = 3; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_)}}, + {29, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_)}}, }}, {{ 65535, 65535 }}, {{ - // float range = 1; - {PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_), 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float point_x = 2; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float point_y = 3; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float radius = 4; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries @@ -10265,23 +14018,54 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ZoomRangeRequest::_table_ = { }}, }; -::uint8_t* ZoomRangeRequest::_InternalSerialize( +::uint8_t* TrackPointRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomRangeRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // float point_x = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_range = this->_internal_range(); - ::uint32_t raw_range; - memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); - if (raw_range != 0) { + float tmp_point_x = this->_internal_point_x(); + ::uint32_t raw_point_x; + memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); + if (raw_point_x != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_point_x(), target); + } + + // float point_y = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_point_y = this->_internal_point_y(); + ::uint32_t raw_point_y; + memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); + if (raw_point_y != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_point_y(), target); + } + + // float radius = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_radius = this->_internal_radius(); + ::uint32_t raw_radius; + memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); + if (raw_radius != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_range(), target); + 4, this->_internal_radius(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10289,115 +14073,165 @@ ::uint8_t* ZoomRangeRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomRangeRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackPointRequest) return target; } -::size_t ZoomRangeRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomRangeRequest) +::size_t TrackPointRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackPointRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // float point_x = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_range = this->_internal_range(); - ::uint32_t raw_range; - memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); - if (raw_range != 0) { + float tmp_point_x = this->_internal_point_x(); + ::uint32_t raw_point_x; + memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); + if (raw_point_x != 0) { + total_size += 5; + } + + // float point_y = 3; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_point_y = this->_internal_point_y(); + ::uint32_t raw_point_y; + memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); + if (raw_point_y != 0) { + total_size += 5; + } + + // float radius = 4; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_radius = this->_internal_radius(); + ::uint32_t raw_radius; + memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); + if (raw_radius != 0) { total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ZoomRangeRequest::_class_data_ = { - ZoomRangeRequest::MergeImpl, +const ::google::protobuf::Message::ClassData TrackPointRequest::_class_data_ = { + TrackPointRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ZoomRangeRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* TrackPointRequest::GetClassData() const { return &_class_data_; } -void ZoomRangeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomRangeRequest) +void TrackPointRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackPointRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_range = from._internal_range(); - ::uint32_t raw_range; - memcpy(&raw_range, &tmp_range, sizeof(tmp_range)); - if (raw_range != 0) { - _this->_internal_set_range(from._internal_range()); + float tmp_point_x = from._internal_point_x(); + ::uint32_t raw_point_x; + memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); + if (raw_point_x != 0) { + _this->_internal_set_point_x(from._internal_point_x()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_point_y = from._internal_point_y(); + ::uint32_t raw_point_y; + memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); + if (raw_point_y != 0) { + _this->_internal_set_point_y(from._internal_point_y()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_radius = from._internal_radius(); + ::uint32_t raw_radius; + memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); + if (raw_radius != 0) { + _this->_internal_set_radius(from._internal_radius()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ZoomRangeRequest::CopyFrom(const ZoomRangeRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomRangeRequest) +void TrackPointRequest::CopyFrom(const TrackPointRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackPointRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ZoomRangeRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool TrackPointRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* ZoomRangeRequest::AccessCachedSize() const { +::_pbi::CachedSize* TrackPointRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void ZoomRangeRequest::InternalSwap(ZoomRangeRequest* PROTOBUF_RESTRICT other) { +void TrackPointRequest::InternalSwap(TrackPointRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.range_, other->_impl_.range_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_) + + sizeof(TrackPointRequest::_impl_.radius_) + - PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } -::google::protobuf::Metadata ZoomRangeRequest::GetMetadata() const { +::google::protobuf::Metadata TrackPointRequest::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[59]); } // =================================================================== -class ZoomRangeResponse::_Internal { +class TrackPointResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const ZoomRangeResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackPointResponse* msg); static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& ZoomRangeResponse::_Internal::camera_result(const ZoomRangeResponse* msg) { +const ::mavsdk::rpc::camera::CameraResult& TrackPointResponse::_Internal::camera_result(const TrackPointResponse* msg) { return *msg->_impl_.camera_result_; } -ZoomRangeResponse::ZoomRangeResponse(::google::protobuf::Arena* arena) +TrackPointResponse::TrackPointResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.ZoomRangeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackPointResponse) } -inline PROTOBUF_NDEBUG_INLINE ZoomRangeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackPointResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ZoomRangeResponse::ZoomRangeResponse( +TrackPointResponse::TrackPointResponse( ::google::protobuf::Arena* arena, - const ZoomRangeResponse& from) + const TrackPointResponse& from) : ::google::protobuf::Message(arena) { - ZoomRangeResponse* const _this = this; + TrackPointResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10407,30 +14241,30 @@ ZoomRangeResponse::ZoomRangeResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.ZoomRangeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackPointResponse) } -inline PROTOBUF_NDEBUG_INLINE ZoomRangeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackPointResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ZoomRangeResponse::SharedCtor(::_pb::Arena* arena) { +inline void TrackPointResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -ZoomRangeResponse::~ZoomRangeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ZoomRangeResponse) +TrackPointResponse::~TrackPointResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackPointResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ZoomRangeResponse::SharedDtor() { +inline void TrackPointResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ZoomRangeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.ZoomRangeResponse) +PROTOBUF_NOINLINE void TrackPointResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackPointResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10445,7 +14279,7 @@ PROTOBUF_NOINLINE void ZoomRangeResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ZoomRangeResponse::_InternalParse( +const char* TrackPointResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10453,9 +14287,9 @@ const char* ZoomRangeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomRangeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackPointResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10464,17 +14298,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomRangeResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ZoomRangeResponse_default_instance_._instance, + &_TrackPointResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(ZoomRangeResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -10482,10 +14316,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ZoomRangeResponse::_table_ = { }}, }; -::uint8_t* ZoomRangeResponse::_InternalSerialize( +::uint8_t* TrackPointResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.ZoomRangeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10502,12 +14336,12 @@ ::uint8_t* ZoomRangeResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.ZoomRangeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackPointResponse) return target; } -::size_t ZoomRangeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ZoomRangeResponse) +::size_t TrackPointResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackPointResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -10524,18 +14358,18 @@ ::size_t ZoomRangeResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ZoomRangeResponse::_class_data_ = { - ZoomRangeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData TrackPointResponse::_class_data_ = { + TrackPointResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ZoomRangeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* TrackPointResponse::GetClassData() const { return &_class_data_; } -void ZoomRangeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.ZoomRangeResponse) +void TrackPointResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackPointResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -10547,86 +14381,86 @@ void ZoomRangeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::g _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ZoomRangeResponse::CopyFrom(const ZoomRangeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.ZoomRangeResponse) +void TrackPointResponse::CopyFrom(const TrackPointResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackPointResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ZoomRangeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool TrackPointResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ZoomRangeResponse::AccessCachedSize() const { +::_pbi::CachedSize* TrackPointResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ZoomRangeResponse::InternalSwap(ZoomRangeResponse* PROTOBUF_RESTRICT other) { +void TrackPointResponse::InternalSwap(TrackPointResponse* PROTOBUF_RESTRICT 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_); } -::google::protobuf::Metadata ZoomRangeResponse::GetMetadata() const { +::google::protobuf::Metadata TrackPointResponse::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[60]); } // =================================================================== -class TrackPointRequest::_Internal { +class TrackRectangleRequest::_Internal { public: }; -TrackPointRequest::TrackPointRequest(::google::protobuf::Arena* arena) +TrackRectangleRequest::TrackRectangleRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackPointRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleRequest) } -TrackPointRequest::TrackPointRequest( - ::google::protobuf::Arena* arena, const TrackPointRequest& from) - : TrackPointRequest(arena) { +TrackRectangleRequest::TrackRectangleRequest( + ::google::protobuf::Arena* arena, const TrackRectangleRequest& from) + : TrackRectangleRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE TrackPointRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackRectangleRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void TrackPointRequest::SharedCtor(::_pb::Arena* arena) { +inline void TrackRectangleRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, point_x_), + offsetof(Impl_, camera_id_), 0, - offsetof(Impl_, radius_) - - offsetof(Impl_, point_x_) + - sizeof(Impl_::radius_)); + offsetof(Impl_, bottom_right_y_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::bottom_right_y_)); } -TrackPointRequest::~TrackPointRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackPointRequest) +TrackRectangleRequest::~TrackRectangleRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void TrackPointRequest::SharedDtor() { +inline void TrackRectangleRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void TrackPointRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackPointRequest) +PROTOBUF_NOINLINE void TrackRectangleRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackRectangleRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.point_x_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.radius_) - - reinterpret_cast(&_impl_.point_x_)) + sizeof(_impl_.radius_)); + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.bottom_right_y_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.bottom_right_y_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* TrackPointRequest::_InternalParse( +const char* TrackRectangleRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10634,41 +14468,55 @@ const char* TrackPointRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> TrackPointRequest::_table_ = { +const ::_pbi::TcParseTable<3, 5, 0, 0, 2> TrackRectangleRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 5, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967264, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 5, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_TrackPointRequest_default_instance_._instance, + &_TrackRectangleRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // float point_x = 1; + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TrackRectangleRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.camera_id_)}}, + // float top_left_x = 2; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_x_)}}, + // float top_left_y = 3; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_)}}, - // float point_y = 2; + {29, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_y_)}}, + // float bottom_right_x = 4; {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_)}}, - // float radius = 3; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_x_)}}, + // float bottom_right_y = 5; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_)}}, + {45, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_)}}, + {::_pbi::TcParser::MiniParse, {}}, + {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // float point_x = 1; - {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_), 0, 0, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float top_left_x = 2; + {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_x_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float point_y = 2; - {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_), 0, 0, + // float top_left_y = 3; + {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_y_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float radius = 3; - {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_), 0, 0, + // float bottom_right_x = 4; + {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_x_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float bottom_right_y = 5; + {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries @@ -10676,47 +14524,66 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> TrackPointRequest::_table_ = { }}, }; -::uint8_t* TrackPointRequest::_InternalSerialize( +::uint8_t* TrackRectangleRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float point_x = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // float top_left_x = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_x = this->_internal_point_x(); - ::uint32_t raw_point_x; - memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); - if (raw_point_x != 0) { + float tmp_top_left_x = this->_internal_top_left_x(); + ::uint32_t raw_top_left_x; + memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); + if (raw_top_left_x != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_point_x(), target); + 2, this->_internal_top_left_x(), target); } - // float point_y = 2; + // float top_left_y = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_y = this->_internal_point_y(); - ::uint32_t raw_point_y; - memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); - if (raw_point_y != 0) { + float tmp_top_left_y = this->_internal_top_left_y(); + ::uint32_t raw_top_left_y; + memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); + if (raw_top_left_y != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_point_y(), target); + 3, this->_internal_top_left_y(), target); } - // float radius = 3; + // float bottom_right_x = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_radius = this->_internal_radius(); - ::uint32_t raw_radius; - memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); - if (raw_radius != 0) { + float tmp_bottom_right_x = this->_internal_bottom_right_x(); + ::uint32_t raw_bottom_right_x; + memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); + if (raw_bottom_right_x != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this->_internal_bottom_right_x(), target); + } + + // float bottom_right_y = 5; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_bottom_right_y = this->_internal_bottom_right_y(); + ::uint32_t raw_bottom_right_y; + memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); + if (raw_bottom_right_y != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_radius(), target); + 5, this->_internal_bottom_right_y(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10724,156 +14591,183 @@ ::uint8_t* TrackPointRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackPointRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackRectangleRequest) return target; } -::size_t TrackPointRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackPointRequest) +::size_t TrackRectangleRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackRectangleRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float point_x = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // float top_left_x = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_x = this->_internal_point_x(); - ::uint32_t raw_point_x; - memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); - if (raw_point_x != 0) { + float tmp_top_left_x = this->_internal_top_left_x(); + ::uint32_t raw_top_left_x; + memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); + if (raw_top_left_x != 0) { total_size += 5; } - // float point_y = 2; + // float top_left_y = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_y = this->_internal_point_y(); - ::uint32_t raw_point_y; - memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); - if (raw_point_y != 0) { + float tmp_top_left_y = this->_internal_top_left_y(); + ::uint32_t raw_top_left_y; + memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); + if (raw_top_left_y != 0) { total_size += 5; } - // float radius = 3; + // float bottom_right_x = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_radius = this->_internal_radius(); - ::uint32_t raw_radius; - memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); - if (raw_radius != 0) { + float tmp_bottom_right_x = this->_internal_bottom_right_x(); + ::uint32_t raw_bottom_right_x; + memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); + if (raw_bottom_right_x != 0) { + total_size += 5; + } + + // float bottom_right_y = 5; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_bottom_right_y = this->_internal_bottom_right_y(); + ::uint32_t raw_bottom_right_y; + memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); + if (raw_bottom_right_y != 0) { total_size += 5; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData TrackPointRequest::_class_data_ = { - TrackPointRequest::MergeImpl, +const ::google::protobuf::Message::ClassData TrackRectangleRequest::_class_data_ = { + TrackRectangleRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* TrackPointRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* TrackRectangleRequest::GetClassData() const { return &_class_data_; } -void TrackPointRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackPointRequest) +void TrackRectangleRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackRectangleRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_x = from._internal_point_x(); - ::uint32_t raw_point_x; - memcpy(&raw_point_x, &tmp_point_x, sizeof(tmp_point_x)); - if (raw_point_x != 0) { - _this->_internal_set_point_x(from._internal_point_x()); + float tmp_top_left_x = from._internal_top_left_x(); + ::uint32_t raw_top_left_x; + memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); + if (raw_top_left_x != 0) { + _this->_internal_set_top_left_x(from._internal_top_left_x()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_point_y = from._internal_point_y(); - ::uint32_t raw_point_y; - memcpy(&raw_point_y, &tmp_point_y, sizeof(tmp_point_y)); - if (raw_point_y != 0) { - _this->_internal_set_point_y(from._internal_point_y()); + float tmp_top_left_y = from._internal_top_left_y(); + ::uint32_t raw_top_left_y; + memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); + if (raw_top_left_y != 0) { + _this->_internal_set_top_left_y(from._internal_top_left_y()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_radius = from._internal_radius(); - ::uint32_t raw_radius; - memcpy(&raw_radius, &tmp_radius, sizeof(tmp_radius)); - if (raw_radius != 0) { - _this->_internal_set_radius(from._internal_radius()); + float tmp_bottom_right_x = from._internal_bottom_right_x(); + ::uint32_t raw_bottom_right_x; + memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); + if (raw_bottom_right_x != 0) { + _this->_internal_set_bottom_right_x(from._internal_bottom_right_x()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_bottom_right_y = from._internal_bottom_right_y(); + ::uint32_t raw_bottom_right_y; + memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); + if (raw_bottom_right_y != 0) { + _this->_internal_set_bottom_right_y(from._internal_bottom_right_y()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void TrackPointRequest::CopyFrom(const TrackPointRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackPointRequest) +void TrackRectangleRequest::CopyFrom(const TrackRectangleRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackRectangleRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool TrackPointRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool TrackRectangleRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* TrackPointRequest::AccessCachedSize() const { +::_pbi::CachedSize* TrackRectangleRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void TrackPointRequest::InternalSwap(TrackPointRequest* PROTOBUF_RESTRICT other) { +void TrackRectangleRequest::InternalSwap(TrackRectangleRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_) - + sizeof(TrackPointRequest::_impl_.radius_) - - PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_)>( - reinterpret_cast(&_impl_.point_x_), - reinterpret_cast(&other->_impl_.point_x_)); + PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_) + + sizeof(TrackRectangleRequest::_impl_.bottom_right_y_) + - PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } -::google::protobuf::Metadata TrackPointRequest::GetMetadata() const { +::google::protobuf::Metadata TrackRectangleRequest::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[61]); } // =================================================================== -class TrackPointResponse::_Internal { +class TrackRectangleResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackPointResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackRectangleResponse* msg); static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& TrackPointResponse::_Internal::camera_result(const TrackPointResponse* msg) { +const ::mavsdk::rpc::camera::CameraResult& TrackRectangleResponse::_Internal::camera_result(const TrackRectangleResponse* msg) { return *msg->_impl_.camera_result_; } -TrackPointResponse::TrackPointResponse(::google::protobuf::Arena* arena) +TrackRectangleResponse::TrackRectangleResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackPointResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackPointResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackRectangleResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -TrackPointResponse::TrackPointResponse( +TrackRectangleResponse::TrackRectangleResponse( ::google::protobuf::Arena* arena, - const TrackPointResponse& from) + const TrackRectangleResponse& from) : ::google::protobuf::Message(arena) { - TrackPointResponse* const _this = this; + TrackRectangleResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10883,30 +14777,30 @@ TrackPointResponse::TrackPointResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackPointResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackRectangleResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackPointResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackRectangleResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void TrackPointResponse::SharedCtor(::_pb::Arena* arena) { +inline void TrackRectangleResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -TrackPointResponse::~TrackPointResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackPointResponse) +TrackRectangleResponse::~TrackRectangleResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void TrackPointResponse::SharedDtor() { +inline void TrackRectangleResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void TrackPointResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackPointResponse) +PROTOBUF_NOINLINE void TrackRectangleResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackRectangleResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10921,7 +14815,7 @@ PROTOBUF_NOINLINE void TrackPointResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* TrackPointResponse::_InternalParse( +const char* TrackRectangleResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10929,9 +14823,9 @@ const char* TrackPointResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackPointResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackRectangleResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10940,17 +14834,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackPointResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_TrackPointResponse_default_instance_._instance, + &_TrackRectangleResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(TrackPointResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -10958,10 +14852,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackPointResponse::_table_ = { }}, }; -::uint8_t* TrackPointResponse::_InternalSerialize( +::uint8_t* TrackRectangleResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10978,12 +14872,12 @@ ::uint8_t* TrackPointResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackPointResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackRectangleResponse) return target; } -::size_t TrackPointResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackPointResponse) +::size_t TrackRectangleResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackRectangleResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -11000,18 +14894,18 @@ ::size_t TrackPointResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData TrackPointResponse::_class_data_ = { - TrackPointResponse::MergeImpl, +const ::google::protobuf::Message::ClassData TrackRectangleResponse::_class_data_ = { + TrackRectangleResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* TrackPointResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* TrackRectangleResponse::GetClassData() const { return &_class_data_; } -void TrackPointResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackPointResponse) +void TrackRectangleResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackRectangleResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -11023,86 +14917,79 @@ void TrackPointResponse::MergeImpl(::google::protobuf::Message& to_msg, const :: _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void TrackPointResponse::CopyFrom(const TrackPointResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackPointResponse) +void TrackRectangleResponse::CopyFrom(const TrackRectangleResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackRectangleResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool TrackPointResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool TrackRectangleResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* TrackPointResponse::AccessCachedSize() const { +::_pbi::CachedSize* TrackRectangleResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void TrackPointResponse::InternalSwap(TrackPointResponse* PROTOBUF_RESTRICT other) { +void TrackRectangleResponse::InternalSwap(TrackRectangleResponse* PROTOBUF_RESTRICT 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_); } -::google::protobuf::Metadata TrackPointResponse::GetMetadata() const { +::google::protobuf::Metadata TrackRectangleResponse::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[62]); } // =================================================================== -class TrackRectangleRequest::_Internal { +class TrackStopRequest::_Internal { public: }; -TrackRectangleRequest::TrackRectangleRequest(::google::protobuf::Arena* arena) +TrackStopRequest::TrackStopRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackStopRequest) } -TrackRectangleRequest::TrackRectangleRequest( - ::google::protobuf::Arena* arena, const TrackRectangleRequest& from) - : TrackRectangleRequest(arena) { +TrackStopRequest::TrackStopRequest( + ::google::protobuf::Arena* arena, const TrackStopRequest& from) + : TrackStopRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE TrackRectangleRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackStopRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void TrackRectangleRequest::SharedCtor(::_pb::Arena* arena) { +inline void TrackStopRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, top_left_x_), - 0, - offsetof(Impl_, bottom_right_y_) - - offsetof(Impl_, top_left_x_) + - sizeof(Impl_::bottom_right_y_)); + _impl_.camera_id_ = {}; } -TrackRectangleRequest::~TrackRectangleRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleRequest) +TrackStopRequest::~TrackStopRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackStopRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void TrackRectangleRequest::SharedDtor() { +inline void TrackStopRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void TrackRectangleRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackRectangleRequest) +PROTOBUF_NOINLINE void TrackStopRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackStopRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.top_left_x_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.bottom_right_y_) - - reinterpret_cast(&_impl_.top_left_x_)) + sizeof(_impl_.bottom_right_y_)); + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* TrackRectangleRequest::_InternalParse( +const char* TrackStopRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11110,106 +14997,47 @@ const char* TrackRectangleRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 4, 0, 0, 2> TrackRectangleRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> TrackStopRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 4, 24, // max_field_number, fast_idx_mask + 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967280, // skipmap + 4294967294, // skipmap offsetof(decltype(_table_), field_entries), - 4, // num_field_entries + 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_TrackRectangleRequest_default_instance_._instance, + &_TrackStopRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // float bottom_right_y = 4; - {::_pbi::TcParser::FastF32S1, - {37, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_)}}, - // float top_left_x = 1; - {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_x_)}}, - // float top_left_y = 2; - {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_y_)}}, - // float bottom_right_x = 3; - {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_x_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TrackStopRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(TrackStopRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // float top_left_x = 1; - {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_x_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float top_left_y = 2; - {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_y_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float bottom_right_x = 3; - {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_x_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float bottom_right_y = 4; - {PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(TrackStopRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, // no aux_entries {{ }}, }; -::uint8_t* TrackRectangleRequest::_InternalSerialize( +::uint8_t* TrackStopRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackStopRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float top_left_x = 1; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_x = this->_internal_top_left_x(); - ::uint32_t raw_top_left_x; - memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); - if (raw_top_left_x != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_top_left_x(), target); - } - - // float top_left_y = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_y = this->_internal_top_left_y(); - ::uint32_t raw_top_left_y; - memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); - if (raw_top_left_y != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_top_left_y(), target); - } - - // float bottom_right_x = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_x = this->_internal_bottom_right_x(); - ::uint32_t raw_bottom_right_x; - memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); - if (raw_bottom_right_x != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_bottom_right_x(), target); - } - - // float bottom_right_y = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_y = this->_internal_bottom_right_y(); - ::uint32_t raw_bottom_right_y; - memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); - if (raw_bottom_right_y != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_bottom_right_y(), target); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11217,174 +15045,106 @@ ::uint8_t* TrackRectangleRequest::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackRectangleRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackStopRequest) return target; } -::size_t TrackRectangleRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackRectangleRequest) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // float top_left_x = 1; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_x = this->_internal_top_left_x(); - ::uint32_t raw_top_left_x; - memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); - if (raw_top_left_x != 0) { - total_size += 5; - } - - // float top_left_y = 2; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_y = this->_internal_top_left_y(); - ::uint32_t raw_top_left_y; - memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); - if (raw_top_left_y != 0) { - total_size += 5; - } - - // float bottom_right_x = 3; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_x = this->_internal_bottom_right_x(); - ::uint32_t raw_bottom_right_x; - memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); - if (raw_bottom_right_x != 0) { - total_size += 5; - } - - // float bottom_right_y = 4; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_y = this->_internal_bottom_right_y(); - ::uint32_t raw_bottom_right_y; - memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); - if (raw_bottom_right_y != 0) { - total_size += 5; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData TrackRectangleRequest::_class_data_ = { - TrackRectangleRequest::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* TrackRectangleRequest::GetClassData() const { - return &_class_data_; -} - -void TrackRectangleRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackRectangleRequest) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_x = from._internal_top_left_x(); - ::uint32_t raw_top_left_x; - memcpy(&raw_top_left_x, &tmp_top_left_x, sizeof(tmp_top_left_x)); - if (raw_top_left_x != 0) { - _this->_internal_set_top_left_x(from._internal_top_left_x()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_top_left_y = from._internal_top_left_y(); - ::uint32_t raw_top_left_y; - memcpy(&raw_top_left_y, &tmp_top_left_y, sizeof(tmp_top_left_y)); - if (raw_top_left_y != 0) { - _this->_internal_set_top_left_y(from._internal_top_left_y()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_x = from._internal_bottom_right_x(); - ::uint32_t raw_bottom_right_x; - memcpy(&raw_bottom_right_x, &tmp_bottom_right_x, sizeof(tmp_bottom_right_x)); - if (raw_bottom_right_x != 0) { - _this->_internal_set_bottom_right_x(from._internal_bottom_right_x()); +::size_t TrackStopRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackStopRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_bottom_right_y = from._internal_bottom_right_y(); - ::uint32_t raw_bottom_right_y; - memcpy(&raw_bottom_right_y, &tmp_bottom_right_y, sizeof(tmp_bottom_right_y)); - if (raw_bottom_right_y != 0) { - _this->_internal_set_bottom_right_y(from._internal_bottom_right_y()); + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData TrackStopRequest::_class_data_ = { + TrackStopRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* TrackStopRequest::GetClassData() const { + return &_class_data_; +} + +void TrackStopRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackStopRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void TrackRectangleRequest::CopyFrom(const TrackRectangleRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackRectangleRequest) +void TrackStopRequest::CopyFrom(const TrackStopRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackStopRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool TrackRectangleRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool TrackStopRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* TrackRectangleRequest::AccessCachedSize() const { +::_pbi::CachedSize* TrackStopRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void TrackRectangleRequest::InternalSwap(TrackRectangleRequest* PROTOBUF_RESTRICT other) { +void TrackStopRequest::InternalSwap(TrackStopRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.bottom_right_y_) - + sizeof(TrackRectangleRequest::_impl_.bottom_right_y_) - - PROTOBUF_FIELD_OFFSET(TrackRectangleRequest, _impl_.top_left_x_)>( - reinterpret_cast(&_impl_.top_left_x_), - reinterpret_cast(&other->_impl_.top_left_x_)); + swap(_impl_.camera_id_, other->_impl_.camera_id_); } -::google::protobuf::Metadata TrackRectangleRequest::GetMetadata() const { +::google::protobuf::Metadata TrackStopRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[54]); + file_level_metadata_camera_2fcamera_2eproto[63]); } // =================================================================== -class TrackRectangleResponse::_Internal { +class TrackStopResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackRectangleResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackStopResponse* msg); static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& TrackRectangleResponse::_Internal::camera_result(const TrackRectangleResponse* msg) { +const ::mavsdk::rpc::camera::CameraResult& TrackStopResponse::_Internal::camera_result(const TrackStopResponse* msg) { return *msg->_impl_.camera_result_; } -TrackRectangleResponse::TrackRectangleResponse(::google::protobuf::Arena* arena) +TrackStopResponse::TrackStopResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackStopResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackRectangleResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -TrackRectangleResponse::TrackRectangleResponse( +TrackStopResponse::TrackStopResponse( ::google::protobuf::Arena* arena, - const TrackRectangleResponse& from) + const TrackStopResponse& from) : ::google::protobuf::Message(arena) { - TrackRectangleResponse* const _this = this; + TrackStopResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -11394,30 +15154,30 @@ TrackRectangleResponse::TrackRectangleResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackRectangleResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackStopResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackRectangleResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE TrackStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void TrackRectangleResponse::SharedCtor(::_pb::Arena* arena) { +inline void TrackStopResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -TrackRectangleResponse::~TrackRectangleResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleResponse) +TrackStopResponse::~TrackStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackStopResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void TrackRectangleResponse::SharedDtor() { +inline void TrackStopResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void TrackRectangleResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackRectangleResponse) +PROTOBUF_NOINLINE void TrackStopResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackStopResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -11432,7 +15192,7 @@ PROTOBUF_NOINLINE void TrackRectangleResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* TrackRectangleResponse::_InternalParse( +const char* TrackStopResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11440,9 +15200,9 @@ const char* TrackRectangleResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackRectangleResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackStopResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -11451,17 +15211,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackRectangleResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_TrackRectangleResponse_default_instance_._instance, + &_TrackStopResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -11469,19 +15229,192 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackRectangleResponse::_table_ = { }}, }; -::uint8_t* TrackRectangleResponse::_InternalSerialize( +::uint8_t* TrackStopResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackStopResponse) + ::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 = ::google::protobuf::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<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackStopResponse) + return target; +} + +::size_t TrackStopResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackStopResponse) + ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData TrackStopResponse::_class_data_ = { + TrackStopResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* TrackStopResponse::GetClassData() const { + return &_class_data_; +} + +void TrackStopResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackStopResponse) + 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<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void TrackStopResponse::CopyFrom(const TrackStopResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackStopResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool TrackStopResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* TrackStopResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void TrackStopResponse::InternalSwap(TrackStopResponse* PROTOBUF_RESTRICT 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_); +} + +::google::protobuf::Metadata TrackStopResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[64]); +} +// =================================================================== + +class FocusInStartRequest::_Internal { + public: +}; + +FocusInStartRequest::FocusInStartRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusInStartRequest) +} +FocusInStartRequest::FocusInStartRequest( + ::google::protobuf::Arena* arena, const FocusInStartRequest& from) + : FocusInStartRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE FocusInStartRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FocusInStartRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +FocusInStartRequest::~FocusInStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusInStartRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FocusInStartRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void FocusInStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusInStartRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* FocusInStartRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FocusInStartRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_FocusInStartRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FocusInStartRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FocusInStartRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(FocusInStartRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* FocusInStartRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusInStartRequest) ::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 = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11489,144 +15422,106 @@ ::uint8_t* TrackRectangleResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackRectangleResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusInStartRequest) return target; } -::size_t TrackRectangleResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackRectangleResponse) +::size_t FocusInStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusInStartRequest) ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData TrackRectangleResponse::_class_data_ = { - TrackRectangleResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FocusInStartRequest::_class_data_ = { + FocusInStartRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* TrackRectangleResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusInStartRequest::GetClassData() const { return &_class_data_; } -void TrackRectangleResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackRectangleResponse) +void FocusInStartRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FocusInStartRequest) 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()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void TrackRectangleResponse::CopyFrom(const TrackRectangleResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackRectangleResponse) +void FocusInStartRequest::CopyFrom(const FocusInStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusInStartRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool TrackRectangleResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusInStartRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* TrackRectangleResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusInStartRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void TrackRectangleResponse::InternalSwap(TrackRectangleResponse* PROTOBUF_RESTRICT other) { +void FocusInStartRequest::InternalSwap(FocusInStartRequest* PROTOBUF_RESTRICT 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_); -} - -::google::protobuf::Metadata TrackRectangleResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[55]); -} -// =================================================================== - -class TrackStopRequest::_Internal { - public: -}; - -TrackStopRequest::TrackStopRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackStopRequest) -} -TrackStopRequest::TrackStopRequest( - ::google::protobuf::Arena* arena, - const TrackStopRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - TrackStopRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackStopRequest) + swap(_impl_.camera_id_, other->_impl_.camera_id_); } - - - - - - - - -::google::protobuf::Metadata TrackStopRequest::GetMetadata() const { +::google::protobuf::Metadata FocusInStartRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[56]); + file_level_metadata_camera_2fcamera_2eproto[65]); } // =================================================================== -class TrackStopResponse::_Internal { +class FocusInStartResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const TrackStopResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FocusInStartResponse* msg); static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::camera::CameraResult& TrackStopResponse::_Internal::camera_result(const TrackStopResponse* msg) { +const ::mavsdk::rpc::camera::CameraResult& FocusInStartResponse::_Internal::camera_result(const FocusInStartResponse* msg) { return *msg->_impl_.camera_result_; } -TrackStopResponse::TrackStopResponse(::google::protobuf::Arena* arena) +FocusInStartResponse::FocusInStartResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackStopResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusInStartResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackStopResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusInStartResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -TrackStopResponse::TrackStopResponse( +FocusInStartResponse::FocusInStartResponse( ::google::protobuf::Arena* arena, - const TrackStopResponse& from) + const FocusInStartResponse& from) : ::google::protobuf::Message(arena) { - TrackStopResponse* const _this = this; + FocusInStartResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -11636,30 +15531,30 @@ TrackStopResponse::TrackStopResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.TrackStopResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusInStartResponse) } -inline PROTOBUF_NDEBUG_INLINE TrackStopResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusInStartResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void TrackStopResponse::SharedCtor(::_pb::Arena* arena) { +inline void FocusInStartResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -TrackStopResponse::~TrackStopResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackStopResponse) +FocusInStartResponse::~FocusInStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusInStartResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void TrackStopResponse::SharedDtor() { +inline void FocusInStartResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void TrackStopResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.TrackStopResponse) +PROTOBUF_NOINLINE void FocusInStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusInStartResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -11674,7 +15569,7 @@ PROTOBUF_NOINLINE void TrackStopResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* TrackStopResponse::_InternalParse( +const char* FocusInStartResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11682,9 +15577,9 @@ const char* TrackStopResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackStopResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FocusInStartResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -11693,17 +15588,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackStopResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_TrackStopResponse_default_instance_._instance, + &_FocusInStartResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_.camera_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(TrackStopResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -11711,10 +15606,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> TrackStopResponse::_table_ = { }}, }; -::uint8_t* TrackStopResponse::_InternalSerialize( +::uint8_t* FocusInStartResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackStopResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusInStartResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -11731,12 +15626,12 @@ ::uint8_t* TrackStopResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.TrackStopResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusInStartResponse) return target; } -::size_t TrackStopResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.TrackStopResponse) +::size_t FocusInStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusInStartResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -11753,18 +15648,18 @@ ::size_t TrackStopResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData TrackStopResponse::_class_data_ = { - TrackStopResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FocusInStartResponse::_class_data_ = { + FocusInStartResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* TrackStopResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusInStartResponse::GetClassData() const { return &_class_data_; } -void TrackStopResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.TrackStopResponse) +void FocusInStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FocusInStartResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -11776,147 +15671,79 @@ void TrackStopResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::g _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void TrackStopResponse::CopyFrom(const TrackStopResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.TrackStopResponse) +void FocusInStartResponse::CopyFrom(const FocusInStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusInStartResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool TrackStopResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusInStartResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* TrackStopResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusInStartResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void TrackStopResponse::InternalSwap(TrackStopResponse* PROTOBUF_RESTRICT other) { +void FocusInStartResponse::InternalSwap(FocusInStartResponse* PROTOBUF_RESTRICT 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_); } -::google::protobuf::Metadata TrackStopResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[57]); -} -// =================================================================== - -class FocusInStartRequest::_Internal { - public: -}; - -FocusInStartRequest::FocusInStartRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusInStartRequest) -} -FocusInStartRequest::FocusInStartRequest( - ::google::protobuf::Arena* arena, - const FocusInStartRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - FocusInStartRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusInStartRequest) -} - - - - - - - - - -::google::protobuf::Metadata FocusInStartRequest::GetMetadata() const { +::google::protobuf::Metadata FocusInStartResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[58]); + file_level_metadata_camera_2fcamera_2eproto[66]); } // =================================================================== -class FocusInStartResponse::_Internal { +class FocusOutStartRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FocusInStartResponse* msg); - static void set_has_camera_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::camera::CameraResult& FocusInStartResponse::_Internal::camera_result(const FocusInStartResponse* msg) { - return *msg->_impl_.camera_result_; -} -FocusInStartResponse::FocusInStartResponse(::google::protobuf::Arena* arena) +FocusOutStartRequest::FocusOutStartRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusInStartResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusOutStartRequest) } -inline PROTOBUF_NDEBUG_INLINE FocusInStartResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -FocusInStartResponse::FocusInStartResponse( - ::google::protobuf::Arena* arena, - const FocusInStartResponse& from) - : ::google::protobuf::Message(arena) { - FocusInStartResponse* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusInStartResponse) +FocusOutStartRequest::FocusOutStartRequest( + ::google::protobuf::Arena* arena, const FocusOutStartRequest& from) + : FocusOutStartRequest(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE FocusInStartResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusOutStartRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void FocusInStartResponse::SharedCtor(::_pb::Arena* arena) { +inline void FocusOutStartRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_result_ = {}; + _impl_.camera_id_ = {}; } -FocusInStartResponse::~FocusInStartResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusInStartResponse) +FocusOutStartRequest::~FocusOutStartRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusOutStartRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FocusInStartResponse::SharedDtor() { +inline void FocusOutStartRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void FocusInStartResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusInStartResponse) +PROTOBUF_NOINLINE void FocusOutStartRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusOutStartRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - 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(); + (void) cached_has_bits; + + _impl_.camera_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FocusInStartResponse::_InternalParse( +const char* FocusOutStartRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11924,48 +15751,47 @@ const char* FocusInStartResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FocusInStartResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FocusOutStartRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_FocusInStartResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_FocusOutStartRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_.camera_result_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FocusOutStartRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FocusOutStartRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, - }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(FocusOutStartRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* FocusInStartResponse::_InternalSerialize( +::uint8_t* FocusOutStartRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusInStartResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusOutStartRequest) ::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 = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_result(this), - _Internal::camera_result(this).GetCachedSize(), target, stream); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11973,111 +15799,73 @@ ::uint8_t* FocusInStartResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusInStartResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusOutStartRequest) return target; } -::size_t FocusInStartResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusInStartResponse) +::size_t FocusOutStartRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusOutStartRequest) ::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 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FocusInStartResponse::_class_data_ = { - FocusInStartResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FocusOutStartRequest::_class_data_ = { + FocusOutStartRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FocusInStartResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusOutStartRequest::GetClassData() const { return &_class_data_; } -void FocusInStartResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FocusInStartResponse) +void FocusOutStartRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FocusOutStartRequest) 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()); + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void FocusInStartResponse::CopyFrom(const FocusInStartResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusInStartResponse) +void FocusOutStartRequest::CopyFrom(const FocusOutStartRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusOutStartRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FocusInStartResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusOutStartRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* FocusInStartResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusOutStartRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void FocusInStartResponse::InternalSwap(FocusInStartResponse* PROTOBUF_RESTRICT other) { +void FocusOutStartRequest::InternalSwap(FocusOutStartRequest* PROTOBUF_RESTRICT 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_); -} - -::google::protobuf::Metadata FocusInStartResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[59]); -} -// =================================================================== - -class FocusOutStartRequest::_Internal { - public: -}; - -FocusOutStartRequest::FocusOutStartRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusOutStartRequest) -} -FocusOutStartRequest::FocusOutStartRequest( - ::google::protobuf::Arena* arena, - const FocusOutStartRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - FocusOutStartRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusOutStartRequest) + swap(_impl_.camera_id_, other->_impl_.camera_id_); } - - - - - - - - ::google::protobuf::Metadata FocusOutStartRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[60]); + file_level_metadata_camera_2fcamera_2eproto[67]); } // =================================================================== @@ -12284,7 +16072,7 @@ void FocusOutStartResponse::InternalSwap(FocusOutStartResponse* PROTOBUF_RESTRIC ::google::protobuf::Metadata FocusOutStartResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[61]); + file_level_metadata_camera_2fcamera_2eproto[68]); } // =================================================================== @@ -12293,33 +16081,168 @@ class FocusStopRequest::_Internal { }; FocusStopRequest::FocusStopRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { + : ::google::protobuf::Message(arena) { + SharedCtor(arena); // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusStopRequest) } FocusStopRequest::FocusStopRequest( - ::google::protobuf::Arena* arena, - const FocusStopRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - FocusStopRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); + ::google::protobuf::Arena* arena, const FocusStopRequest& from) + : FocusStopRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE FocusStopRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FocusStopRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +FocusStopRequest::~FocusStopRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusStopRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FocusStopRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void FocusStopRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusStopRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.camera_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* FocusStopRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FocusStopRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_FocusStopRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FocusStopRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FocusStopRequest, _impl_.camera_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(FocusStopRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* FocusStopRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusStopRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusStopRequest) + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusStopRequest) + return target; } +::size_t FocusStopRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusStopRequest) + ::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 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} +const ::google::protobuf::Message::ClassData FocusStopRequest::_class_data_ = { + FocusStopRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* FocusStopRequest::GetClassData() const { + return &_class_data_; +} +void FocusStopRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.FocusStopRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} +void FocusStopRequest::CopyFrom(const FocusStopRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusStopRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +PROTOBUF_NOINLINE bool FocusStopRequest::IsInitialized() const { + return true; +} +::_pbi::CachedSize* FocusStopRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void FocusStopRequest::InternalSwap(FocusStopRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.camera_id_, other->_impl_.camera_id_); +} ::google::protobuf::Metadata FocusStopRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[62]); + file_level_metadata_camera_2fcamera_2eproto[69]); } // =================================================================== @@ -12526,7 +16449,7 @@ void FocusStopResponse::InternalSwap(FocusStopResponse* PROTOBUF_RESTRICT other) ::google::protobuf::Metadata FocusStopResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[63]); + file_level_metadata_camera_2fcamera_2eproto[70]); } // =================================================================== @@ -12551,7 +16474,12 @@ inline PROTOBUF_NDEBUG_INLINE FocusRangeRequest::Impl_::Impl_( inline void FocusRangeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.range_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, range_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::range_)); } FocusRangeRequest::~FocusRangeRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusRangeRequest) @@ -12570,7 +16498,9 @@ PROTOBUF_NOINLINE void FocusRangeRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.range_ = 0; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.range_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.range_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -12582,27 +16512,33 @@ const char* FocusRangeRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FocusRangeRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> FocusRangeRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_FocusRangeRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // float range = 1; + // float range = 2; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_)}}, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FocusRangeRequest, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.camera_id_)}}, }}, {{ 65535, 65535 }}, {{ - // float range = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float range = 2; {PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, @@ -12618,7 +16554,14 @@ ::uint8_t* FocusRangeRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // float range = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_range = this->_internal_range(); @@ -12627,7 +16570,7 @@ ::uint8_t* FocusRangeRequest::_InternalSerialize( if (raw_range != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_range(), target); + 2, this->_internal_range(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -12647,7 +16590,13 @@ ::size_t FocusRangeRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float range = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // float range = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_range = this->_internal_range(); @@ -12676,6 +16625,9 @@ void FocusRangeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::g ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_range = from._internal_range(); @@ -12704,13 +16656,18 @@ ::_pbi::CachedSize* FocusRangeRequest::AccessCachedSize() const { void FocusRangeRequest::InternalSwap(FocusRangeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.range_, other->_impl_.range_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_) + + sizeof(FocusRangeRequest::_impl_.range_) + - PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::Metadata FocusRangeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[64]); + file_level_metadata_camera_2fcamera_2eproto[71]); } // =================================================================== @@ -12917,7 +16874,7 @@ void FocusRangeResponse::InternalSwap(FocusRangeResponse* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata FocusRangeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, - file_level_metadata_camera_2fcamera_2eproto[65]); + file_level_metadata_camera_2fcamera_2eproto[72]); } // =================================================================== @@ -13133,7 +17090,7 @@ void CameraResult::InternalSwap(CameraResult* PROTOBUF_RESTRICT other) { ::google::protobuf::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[66]); + file_level_metadata_camera_2fcamera_2eproto[73]); } // =================================================================== @@ -13437,7 +17394,7 @@ void Position::InternalSwap(Position* PROTOBUF_RESTRICT other) { ::google::protobuf::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[67]); + file_level_metadata_camera_2fcamera_2eproto[74]); } // =================================================================== @@ -13741,7 +17698,7 @@ void Quaternion::InternalSwap(Quaternion* PROTOBUF_RESTRICT other) { ::google::protobuf::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[68]); + file_level_metadata_camera_2fcamera_2eproto[75]); } // =================================================================== @@ -14010,7 +17967,7 @@ void EulerAngle::InternalSwap(EulerAngle* PROTOBUF_RESTRICT other) { ::google::protobuf::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[69]); + file_level_metadata_camera_2fcamera_2eproto[76]); } // =================================================================== @@ -14421,7 +18378,7 @@ void CaptureInfo::InternalSwap(CaptureInfo* PROTOBUF_RESTRICT other) { ::google::protobuf::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[70]); + file_level_metadata_camera_2fcamera_2eproto[77]); } // =================================================================== @@ -14794,7 +18751,7 @@ void VideoStreamSettings::InternalSwap(VideoStreamSettings* PROTOBUF_RESTRICT ot ::google::protobuf::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[71]); + file_level_metadata_camera_2fcamera_2eproto[78]); } // =================================================================== @@ -14837,11 +18794,11 @@ VideoStreamInfo::VideoStreamInfo( ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamSettings>(arena, *from._impl_.settings_) : nullptr; ::memcpy(reinterpret_cast(&_impl_) + - offsetof(Impl_, status_), + offsetof(Impl_, camera_id_), reinterpret_cast(&from._impl_) + - offsetof(Impl_, status_), + offsetof(Impl_, camera_id_), offsetof(Impl_, spectrum_) - - offsetof(Impl_, status_) + + offsetof(Impl_, camera_id_) + sizeof(Impl_::spectrum_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.VideoStreamInfo) @@ -14883,9 +18840,9 @@ PROTOBUF_NOINLINE void VideoStreamInfo::Clear() { ABSL_DCHECK(_impl_.settings_ != nullptr); _impl_.settings_->Clear(); } - ::memset(&_impl_.status_, 0, static_cast<::size_t>( + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.spectrum_) - - reinterpret_cast(&_impl_.status_)) + sizeof(_impl_.spectrum_)); + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.spectrum_)); _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -14898,40 +18855,45 @@ const char* VideoStreamInfo::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 1, 0, 2> VideoStreamInfo::_table_ = { +const ::_pbi::TcParseTable<2, 4, 1, 0, 2> VideoStreamInfo::_table_ = { { PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_._has_bits_), 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 4, 24, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967280, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 4, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), &_VideoStreamInfo_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.spectrum_), 63>(), + {32, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_)}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.camera_id_)}}, + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)}}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + {18, 0, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_)}}, + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.status_), 63>(), - {16, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_)}}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(VideoStreamInfo, _impl_.spectrum_), 63>(), - {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_)}}, + {24, 63, 0, PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.camera_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.settings_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.status_), -1, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; {PROTOBUF_FIELD_OFFSET(VideoStreamInfo, _impl_.spectrum_), -1, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, {{ @@ -14947,26 +18909,33 @@ ::uint8_t* VideoStreamInfo::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::settings(this), + 2, _Internal::settings(this), _Internal::settings(this).GetCachedSize(), target, stream); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; if (this->_internal_status() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 2, this->_internal_status(), target); + 3, this->_internal_status(), target); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; if (this->_internal_spectrum() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 3, this->_internal_spectrum(), target); + 4, this->_internal_spectrum(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -14986,20 +18955,26 @@ ::size_t VideoStreamInfo::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.camera.VideoStreamSettings settings = 1; + // .mavsdk.rpc.camera.VideoStreamSettings settings = 2; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.settings_); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 2; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamStatus status = 3; if (this->_internal_status() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_status()); } - // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 3; + // .mavsdk.rpc.camera.VideoStreamInfo.VideoStreamSpectrum spectrum = 4; if (this->_internal_spectrum() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_spectrum()); @@ -15028,6 +19003,9 @@ void VideoStreamInfo::MergeImpl(::google::protobuf::Message& to_msg, const ::goo _this->_internal_mutable_settings()->::mavsdk::rpc::camera::VideoStreamSettings::MergeFrom( from._internal_settings()); } + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_status() != 0) { _this->_internal_set_status(from._internal_status()); } @@ -15066,7 +19044,7 @@ void VideoStreamInfo::InternalSwap(VideoStreamInfo* PROTOBUF_RESTRICT other) { ::google::protobuf::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[72]); + file_level_metadata_camera_2fcamera_2eproto[79]); } // =================================================================== @@ -15095,11 +19073,11 @@ Status::Status( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::memcpy(reinterpret_cast(&_impl_) + - offsetof(Impl_, video_on_), + offsetof(Impl_, camera_id_), reinterpret_cast(&from._impl_) + - offsetof(Impl_, video_on_), + offsetof(Impl_, camera_id_), offsetof(Impl_, storage_type_) - - offsetof(Impl_, video_on_) + + offsetof(Impl_, camera_id_) + sizeof(Impl_::storage_type_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.Status) @@ -15113,10 +19091,10 @@ inline PROTOBUF_NDEBUG_INLINE Status::Impl_::Impl_( inline void Status::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, video_on_), + offsetof(Impl_, camera_id_), 0, offsetof(Impl_, storage_type_) - - offsetof(Impl_, video_on_) + + offsetof(Impl_, camera_id_) + sizeof(Impl_::storage_type_)); } Status::~Status() { @@ -15138,9 +19116,9 @@ PROTOBUF_NOINLINE void Status::Clear() { (void) cached_has_bits; _impl_.media_folder_name_.ClearToEmpty(); - ::memset(&_impl_.video_on_, 0, static_cast<::size_t>( + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.storage_type_) - - reinterpret_cast(&_impl_.video_on_)) + sizeof(_impl_.storage_type_)); + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.storage_type_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -15152,52 +19130,54 @@ const char* Status::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<4, 10, 0, 58, 2> Status::_table_ = { +const ::_pbi::TcParseTable<4, 11, 0, 58, 2> Status::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 10, 120, // max_field_number, fast_idx_mask + 11, 120, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294966272, // skipmap + 4294965248, // skipmap offsetof(decltype(_table_), field_entries), - 10, // num_field_entries + 11, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_Status_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // bool video_on = 1; + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Status, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.camera_id_)}}, + // bool video_on = 2; {::_pbi::TcParser::SingularVarintNoZag1(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.video_on_)}}, - // bool photo_interval_on = 2; + {16, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.video_on_)}}, + // bool photo_interval_on = 3; {::_pbi::TcParser::SingularVarintNoZag1(), - {16, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.photo_interval_on_)}}, - // float used_storage_mib = 3; + {24, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.photo_interval_on_)}}, + // float used_storage_mib = 4; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.used_storage_mib_)}}, - // float available_storage_mib = 4; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.used_storage_mib_)}}, + // float available_storage_mib = 5; {::_pbi::TcParser::FastF32S1, - {37, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.available_storage_mib_)}}, - // float total_storage_mib = 5; + {45, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.available_storage_mib_)}}, + // float total_storage_mib = 6; {::_pbi::TcParser::FastF32S1, - {45, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.total_storage_mib_)}}, - // float recording_time_s = 6; + {53, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.total_storage_mib_)}}, + // float recording_time_s = 7; {::_pbi::TcParser::FastF32S1, - {53, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.recording_time_s_)}}, - // string media_folder_name = 7; + {61, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.recording_time_s_)}}, + // string media_folder_name = 8; {::_pbi::TcParser::FastUS1, - {58, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.media_folder_name_)}}, - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + {66, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.media_folder_name_)}}, + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 9; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Status, _impl_.storage_status_), 63>(), - {64, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_status_)}}, - // uint32 storage_id = 9; + {72, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_status_)}}, + // uint32 storage_id = 10; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Status, _impl_.storage_id_), 63>(), - {72, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_id_)}}, - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + {80, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_id_)}}, + // .mavsdk.rpc.camera.Status.StorageType storage_type = 11; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Status, _impl_.storage_type_), 63>(), - {80, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_type_)}}, - {::_pbi::TcParser::MiniParse, {}}, + {88, 63, 0, PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_type_)}}, {::_pbi::TcParser::MiniParse, {}}, {::_pbi::TcParser::MiniParse, {}}, {::_pbi::TcParser::MiniParse, {}}, @@ -15205,40 +19185,43 @@ const ::_pbi::TcParseTable<4, 10, 0, 58, 2> Status::_table_ = { }}, {{ 65535, 65535 }}, {{ - // bool video_on = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(Status, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // bool video_on = 2; {PROTOBUF_FIELD_OFFSET(Status, _impl_.video_on_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kBool)}, - // bool photo_interval_on = 2; + // bool photo_interval_on = 3; {PROTOBUF_FIELD_OFFSET(Status, _impl_.photo_interval_on_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kBool)}, - // float used_storage_mib = 3; + // float used_storage_mib = 4; {PROTOBUF_FIELD_OFFSET(Status, _impl_.used_storage_mib_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float available_storage_mib = 4; + // float available_storage_mib = 5; {PROTOBUF_FIELD_OFFSET(Status, _impl_.available_storage_mib_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float total_storage_mib = 5; + // float total_storage_mib = 6; {PROTOBUF_FIELD_OFFSET(Status, _impl_.total_storage_mib_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float recording_time_s = 6; + // float recording_time_s = 7; {PROTOBUF_FIELD_OFFSET(Status, _impl_.recording_time_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // string media_folder_name = 7; + // string media_folder_name = 8; {PROTOBUF_FIELD_OFFSET(Status, _impl_.media_folder_name_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 9; {PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_status_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // uint32 storage_id = 9; + // uint32 storage_id = 10; {PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUInt32)}, - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + // .mavsdk.rpc.camera.Status.StorageType storage_type = 11; {PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_type_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, // no aux_entries {{ - "\30\0\0\0\0\0\0\21\0\0\0\0\0\0\0\0" + "\30\0\0\0\0\0\0\0\21\0\0\0\0\0\0\0" "mavsdk.rpc.camera.Status" "media_folder_name" }}, @@ -15251,21 +19234,28 @@ ::uint8_t* Status::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // bool video_on = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // bool video_on = 2; if (this->_internal_video_on() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteBoolToArray( - 1, this->_internal_video_on(), target); + 2, this->_internal_video_on(), target); } - // bool photo_interval_on = 2; + // bool photo_interval_on = 3; if (this->_internal_photo_interval_on() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteBoolToArray( - 2, this->_internal_photo_interval_on(), target); + 3, this->_internal_photo_interval_on(), target); } - // float used_storage_mib = 3; + // float used_storage_mib = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_used_storage_mib = this->_internal_used_storage_mib(); @@ -15274,10 +19264,10 @@ ::uint8_t* Status::_InternalSerialize( if (raw_used_storage_mib != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_used_storage_mib(), target); + 4, this->_internal_used_storage_mib(), target); } - // float available_storage_mib = 4; + // float available_storage_mib = 5; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_available_storage_mib = this->_internal_available_storage_mib(); @@ -15286,10 +19276,10 @@ ::uint8_t* Status::_InternalSerialize( if (raw_available_storage_mib != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_available_storage_mib(), target); + 5, this->_internal_available_storage_mib(), target); } - // float total_storage_mib = 5; + // float total_storage_mib = 6; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_total_storage_mib = this->_internal_total_storage_mib(); @@ -15298,10 +19288,10 @@ ::uint8_t* Status::_InternalSerialize( if (raw_total_storage_mib != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 5, this->_internal_total_storage_mib(), target); + 6, this->_internal_total_storage_mib(), target); } - // float recording_time_s = 6; + // float recording_time_s = 7; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_recording_time_s = this->_internal_recording_time_s(); @@ -15310,36 +19300,36 @@ ::uint8_t* Status::_InternalSerialize( if (raw_recording_time_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 6, this->_internal_recording_time_s(), target); + 7, this->_internal_recording_time_s(), target); } - // string media_folder_name = 7; + // string media_folder_name = 8; if (!this->_internal_media_folder_name().empty()) { const std::string& _s = this->_internal_media_folder_name(); ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera.Status.media_folder_name"); - target = stream->WriteStringMaybeAliased(7, _s, target); + target = stream->WriteStringMaybeAliased(8, _s, target); } - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 9; if (this->_internal_storage_status() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 8, this->_internal_storage_status(), target); + 9, this->_internal_storage_status(), target); } - // uint32 storage_id = 9; + // uint32 storage_id = 10; if (this->_internal_storage_id() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteUInt32ToArray( - 9, this->_internal_storage_id(), target); + 10, this->_internal_storage_id(), target); } - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + // .mavsdk.rpc.camera.Status.StorageType storage_type = 11; if (this->_internal_storage_type() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 10, this->_internal_storage_type(), target); + 11, this->_internal_storage_type(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -15359,23 +19349,29 @@ ::size_t Status::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string media_folder_name = 7; + // string media_folder_name = 8; if (!this->_internal_media_folder_name().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( this->_internal_media_folder_name()); } - // bool video_on = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // bool video_on = 2; if (this->_internal_video_on() != 0) { total_size += 2; } - // bool photo_interval_on = 2; + // bool photo_interval_on = 3; if (this->_internal_photo_interval_on() != 0) { total_size += 2; } - // float used_storage_mib = 3; + // float used_storage_mib = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_used_storage_mib = this->_internal_used_storage_mib(); @@ -15385,7 +19381,7 @@ ::size_t Status::ByteSizeLong() const { total_size += 5; } - // float available_storage_mib = 4; + // float available_storage_mib = 5; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_available_storage_mib = this->_internal_available_storage_mib(); @@ -15395,7 +19391,7 @@ ::size_t Status::ByteSizeLong() const { total_size += 5; } - // float total_storage_mib = 5; + // float total_storage_mib = 6; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_total_storage_mib = this->_internal_total_storage_mib(); @@ -15405,7 +19401,7 @@ ::size_t Status::ByteSizeLong() const { total_size += 5; } - // float recording_time_s = 6; + // float recording_time_s = 7; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_recording_time_s = this->_internal_recording_time_s(); @@ -15415,19 +19411,19 @@ ::size_t Status::ByteSizeLong() const { total_size += 5; } - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 9; if (this->_internal_storage_status() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_status()); } - // uint32 storage_id = 9; + // uint32 storage_id = 10; if (this->_internal_storage_id() != 0) { total_size += ::_pbi::WireFormatLite::UInt32SizePlusOne( this->_internal_storage_id()); } - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + // .mavsdk.rpc.camera.Status.StorageType storage_type = 11; if (this->_internal_storage_type() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_storage_type()); @@ -15455,6 +19451,9 @@ void Status::MergeImpl(::google::protobuf::Message& to_msg, const ::google::prot if (!from._internal_media_folder_name().empty()) { _this->_internal_set_media_folder_name(from._internal_media_folder_name()); } + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_video_on() != 0) { _this->_internal_set_video_on(from._internal_video_on()); } @@ -15528,15 +19527,15 @@ void Status::InternalSwap(Status* PROTOBUF_RESTRICT other) { ::google::protobuf::internal::memswap< PROTOBUF_FIELD_OFFSET(Status, _impl_.storage_type_) + sizeof(Status::_impl_.storage_type_) - - PROTOBUF_FIELD_OFFSET(Status, _impl_.video_on_)>( - reinterpret_cast(&_impl_.video_on_), - reinterpret_cast(&other->_impl_.video_on_)); + - PROTOBUF_FIELD_OFFSET(Status, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::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[73]); + file_level_metadata_camera_2fcamera_2eproto[80]); } // =================================================================== @@ -15755,7 +19754,7 @@ void Option::InternalSwap(Option* PROTOBUF_RESTRICT other) { ::google::protobuf::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[74]); + file_level_metadata_camera_2fcamera_2eproto[81]); } // =================================================================== @@ -16057,7 +20056,7 @@ void Setting::InternalSwap(Setting* PROTOBUF_RESTRICT other) { ::google::protobuf::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[75]); + file_level_metadata_camera_2fcamera_2eproto[82]); } // =================================================================== @@ -16087,7 +20086,13 @@ SettingOptions::SettingOptions( _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - _impl_.is_range_ = from._impl_.is_range_; + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, camera_id_), + offsetof(Impl_, is_range_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::is_range_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SettingOptions) } @@ -16101,7 +20106,12 @@ inline PROTOBUF_NDEBUG_INLINE SettingOptions::Impl_::Impl_( inline void SettingOptions::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.is_range_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, camera_id_), + 0, + offsetof(Impl_, is_range_) - + offsetof(Impl_, camera_id_) + + sizeof(Impl_::is_range_)); } SettingOptions::~SettingOptions() { // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SettingOptions) @@ -16125,7 +20135,9 @@ PROTOBUF_NOINLINE void SettingOptions::Clear() { _impl_.options_.Clear(); _impl_.setting_id_.ClearToEmpty(); _impl_.setting_description_.ClearToEmpty(); - _impl_.is_range_ = false; + ::memset(&_impl_.camera_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.is_range_) - + reinterpret_cast(&_impl_.camera_id_)) + sizeof(_impl_.is_range_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -16137,51 +20149,60 @@ const char* SettingOptions::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 4, 1, 70, 2> SettingOptions::_table_ = { +const ::_pbi::TcParseTable<3, 5, 1, 70, 2> SettingOptions::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 4, 24, // max_field_number, fast_idx_mask + 5, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967280, // skipmap + 4294967264, // skipmap offsetof(decltype(_table_), field_entries), - 4, // num_field_entries + 5, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), &_SettingOptions_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // bool is_range = 4; - {::_pbi::TcParser::SingularVarintNoZag1(), - {32, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.is_range_)}}, - // string setting_id = 1; + {::_pbi::TcParser::MiniParse, {}}, + // int32 camera_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SettingOptions, _impl_.camera_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.camera_id_)}}, + // string setting_id = 2; {::_pbi::TcParser::FastUS1, - {10, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_id_)}}, - // string setting_description = 2; + {18, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_id_)}}, + // string setting_description = 3; {::_pbi::TcParser::FastUS1, - {18, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_description_)}}, - // repeated .mavsdk.rpc.camera.Option options = 3; + {26, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_description_)}}, + // repeated .mavsdk.rpc.camera.Option options = 4; {::_pbi::TcParser::FastMtR1, - {26, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.options_)}}, + {34, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.options_)}}, + // bool is_range = 5; + {::_pbi::TcParser::SingularVarintNoZag1(), + {40, 63, 0, PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.is_range_)}}, + {::_pbi::TcParser::MiniParse, {}}, + {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // string setting_id = 1; + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // string setting_id = 2; {PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_id_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // string setting_description = 2; + // string setting_description = 3; {PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.setting_description_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, - // repeated .mavsdk.rpc.camera.Option options = 3; + // repeated .mavsdk.rpc.camera.Option options = 4; {PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.options_), 0, 0, (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, - // bool is_range = 4; + // bool is_range = 5; {PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.is_range_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kBool)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Option>()}, }}, {{ - "\40\12\23\0\0\0\0\0" + "\40\0\12\23\0\0\0\0" "mavsdk.rpc.camera.SettingOptions" "setting_id" "setting_description" @@ -16195,35 +20216,42 @@ ::uint8_t* SettingOptions::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // string setting_id = 1; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_camera_id(), target); + } + + // string setting_id = 2; if (!this->_internal_setting_id().empty()) { const std::string& _s = this->_internal_setting_id(); ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera.SettingOptions.setting_id"); - target = stream->WriteStringMaybeAliased(1, _s, target); + target = stream->WriteStringMaybeAliased(2, _s, target); } - // string setting_description = 2; + // string setting_description = 3; if (!this->_internal_setting_description().empty()) { const std::string& _s = this->_internal_setting_description(); ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.camera.SettingOptions.setting_description"); - target = stream->WriteStringMaybeAliased(2, _s, target); + target = stream->WriteStringMaybeAliased(3, _s, target); } - // repeated .mavsdk.rpc.camera.Option options = 3; + // repeated .mavsdk.rpc.camera.Option options = 4; for (unsigned i = 0, n = static_cast(this->_internal_options_size()); i < n; i++) { const auto& repfield = this->_internal_options().Get(i); target = ::google::protobuf::internal::WireFormatLite:: - InternalWriteMessage(3, repfield, repfield.GetCachedSize(), target, stream); + InternalWriteMessage(4, repfield, repfield.GetCachedSize(), target, stream); } - // bool is_range = 4; + // bool is_range = 5; if (this->_internal_is_range() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteBoolToArray( - 4, this->_internal_is_range(), target); + 5, this->_internal_is_range(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -16243,25 +20271,31 @@ ::size_t SettingOptions::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // repeated .mavsdk.rpc.camera.Option options = 3; + // repeated .mavsdk.rpc.camera.Option options = 4; total_size += 1UL * this->_internal_options_size(); for (const auto& msg : this->_internal_options()) { total_size += ::google::protobuf::internal::WireFormatLite::MessageSize(msg); } - // string setting_id = 1; + // string setting_id = 2; if (!this->_internal_setting_id().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( this->_internal_setting_id()); } - // string setting_description = 2; + // string setting_description = 3; if (!this->_internal_setting_description().empty()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( this->_internal_setting_description()); } - // bool is_range = 4; + // int32 camera_id = 1; + if (this->_internal_camera_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_camera_id()); + } + + // bool is_range = 5; if (this->_internal_is_range() != 0) { total_size += 2; } @@ -16293,6 +20327,9 @@ void SettingOptions::MergeImpl(::google::protobuf::Message& to_msg, const ::goog if (!from._internal_setting_description().empty()) { _this->_internal_set_setting_description(from._internal_setting_description()); } + if (from._internal_camera_id() != 0) { + _this->_internal_set_camera_id(from._internal_camera_id()); + } if (from._internal_is_range() != 0) { _this->_internal_set_is_range(from._internal_is_range()); } @@ -16321,13 +20358,18 @@ void SettingOptions::InternalSwap(SettingOptions* PROTOBUF_RESTRICT other) { _impl_.options_.InternalSwap(&other->_impl_.options_); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.setting_id_, &other->_impl_.setting_id_, arena); ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.setting_description_, &other->_impl_.setting_description_, arena); - swap(_impl_.is_range_, other->_impl_.is_range_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.is_range_) + + sizeof(SettingOptions::_impl_.is_range_) + - PROTOBUF_FIELD_OFFSET(SettingOptions, _impl_.camera_id_)>( + reinterpret_cast(&_impl_.camera_id_), + reinterpret_cast(&other->_impl_.camera_id_)); } ::google::protobuf::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[76]); + file_level_metadata_camera_2fcamera_2eproto[83]); } // =================================================================== @@ -16721,7 +20763,190 @@ void Information::InternalSwap(Information* PROTOBUF_RESTRICT other) { ::google::protobuf::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[77]); + file_level_metadata_camera_2fcamera_2eproto[84]); +} +// =================================================================== + +class CameraList::_Internal { + public: +}; + +CameraList::CameraList(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.CameraList) +} +inline PROTOBUF_NDEBUG_INLINE CameraList::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : cameras_{visibility, arena, from.cameras_}, + _cached_size_{0} {} + +CameraList::CameraList( + ::google::protobuf::Arena* arena, + const CameraList& from) + : ::google::protobuf::Message(arena) { + CameraList* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.CameraList) +} +inline PROTOBUF_NDEBUG_INLINE CameraList::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : cameras_{visibility, arena}, + _cached_size_{0} {} + +inline void CameraList::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); +} +CameraList::~CameraList() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.CameraList) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void CameraList::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void CameraList::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.CameraList) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.cameras_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* CameraList::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraList::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_CameraList_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // repeated .mavsdk.rpc.camera.Information cameras = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(CameraList, _impl_.cameras_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // repeated .mavsdk.rpc.camera.Information cameras = 1; + {PROTOBUF_FIELD_OFFSET(CameraList, _impl_.cameras_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::Information>()}, + }}, {{ + }}, +}; + +::uint8_t* CameraList::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.CameraList) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // repeated .mavsdk.rpc.camera.Information cameras = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_cameras_size()); i < n; i++) { + const auto& repfield = this->_internal_cameras().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, repfield, repfield.GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.CameraList) + return target; +} + +::size_t CameraList::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.CameraList) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // repeated .mavsdk.rpc.camera.Information cameras = 1; + total_size += 1UL * this->_internal_cameras_size(); + for (const auto& msg : this->_internal_cameras()) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData CameraList::_class_data_ = { + CameraList::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* CameraList::GetClassData() const { + return &_class_data_; +} + +void CameraList::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.camera.CameraList) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + _this->_internal_mutable_cameras()->MergeFrom( + from._internal_cameras()); + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void CameraList::CopyFrom(const CameraList& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.CameraList) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool CameraList::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* CameraList::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void CameraList::InternalSwap(CameraList* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + _impl_.cameras_.InternalSwap(&other->_impl_.cameras_); +} + +::google::protobuf::Metadata CameraList::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[85]); } // @@protoc_insertion_point(namespace_scope) } // namespace camera diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index 201b3abdc8..1fd757da8d 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -61,6 +61,12 @@ extern const ::google::protobuf::internal::DescriptorTable namespace mavsdk { namespace rpc { namespace camera { +class CameraList; +struct CameraListDefaultTypeInternal; +extern CameraListDefaultTypeInternal _CameraList_default_instance_; +class CameraListResponse; +struct CameraListResponseDefaultTypeInternal; +extern CameraListResponseDefaultTypeInternal _CameraListResponse_default_instance_; class CameraResult; struct CameraResultDefaultTypeInternal; extern CameraResultDefaultTypeInternal _CameraResult_default_instance_; @@ -106,24 +112,54 @@ extern FormatStorageRequestDefaultTypeInternal _FormatStorageRequest_default_ins class FormatStorageResponse; struct FormatStorageResponseDefaultTypeInternal; extern FormatStorageResponseDefaultTypeInternal _FormatStorageResponse_default_instance_; +class GetCurrentSettingsRequest; +struct GetCurrentSettingsRequestDefaultTypeInternal; +extern GetCurrentSettingsRequestDefaultTypeInternal _GetCurrentSettingsRequest_default_instance_; +class GetCurrentSettingsResponse; +struct GetCurrentSettingsResponseDefaultTypeInternal; +extern GetCurrentSettingsResponseDefaultTypeInternal _GetCurrentSettingsResponse_default_instance_; +class GetModeRequest; +struct GetModeRequestDefaultTypeInternal; +extern GetModeRequestDefaultTypeInternal _GetModeRequest_default_instance_; +class GetModeResponse; +struct GetModeResponseDefaultTypeInternal; +extern GetModeResponseDefaultTypeInternal _GetModeResponse_default_instance_; +class GetPossibleSettingOptionsRequest; +struct GetPossibleSettingOptionsRequestDefaultTypeInternal; +extern GetPossibleSettingOptionsRequestDefaultTypeInternal _GetPossibleSettingOptionsRequest_default_instance_; +class GetPossibleSettingOptionsResponse; +struct GetPossibleSettingOptionsResponseDefaultTypeInternal; +extern GetPossibleSettingOptionsResponseDefaultTypeInternal _GetPossibleSettingOptionsResponse_default_instance_; class GetSettingRequest; struct GetSettingRequestDefaultTypeInternal; extern GetSettingRequestDefaultTypeInternal _GetSettingRequest_default_instance_; class GetSettingResponse; struct GetSettingResponseDefaultTypeInternal; extern GetSettingResponseDefaultTypeInternal _GetSettingResponse_default_instance_; +class GetStatusRequest; +struct GetStatusRequestDefaultTypeInternal; +extern GetStatusRequestDefaultTypeInternal _GetStatusRequest_default_instance_; +class GetStatusResponse; +struct GetStatusResponseDefaultTypeInternal; +extern GetStatusResponseDefaultTypeInternal _GetStatusResponse_default_instance_; +class GetVideoStreamInfoRequest; +struct GetVideoStreamInfoRequestDefaultTypeInternal; +extern GetVideoStreamInfoRequestDefaultTypeInternal _GetVideoStreamInfoRequest_default_instance_; +class GetVideoStreamInfoResponse; +struct GetVideoStreamInfoResponseDefaultTypeInternal; +extern GetVideoStreamInfoResponseDefaultTypeInternal _GetVideoStreamInfoResponse_default_instance_; class Information; struct InformationDefaultTypeInternal; extern InformationDefaultTypeInternal _Information_default_instance_; -class InformationResponse; -struct InformationResponseDefaultTypeInternal; -extern InformationResponseDefaultTypeInternal _InformationResponse_default_instance_; class ListPhotosRequest; struct ListPhotosRequestDefaultTypeInternal; extern ListPhotosRequestDefaultTypeInternal _ListPhotosRequest_default_instance_; class ListPhotosResponse; struct ListPhotosResponseDefaultTypeInternal; extern ListPhotosResponseDefaultTypeInternal _ListPhotosResponse_default_instance_; +class ModeInfo; +struct ModeInfoDefaultTypeInternal; +extern ModeInfoDefaultTypeInternal _ModeInfo_default_instance_; class ModeResponse; struct ModeResponseDefaultTypeInternal; extern ModeResponseDefaultTypeInternal _ModeResponse_default_instance_; @@ -136,12 +172,6 @@ extern PositionDefaultTypeInternal _Position_default_instance_; class PossibleSettingOptionsResponse; struct PossibleSettingOptionsResponseDefaultTypeInternal; extern PossibleSettingOptionsResponseDefaultTypeInternal _PossibleSettingOptionsResponse_default_instance_; -class PrepareRequest; -struct PrepareRequestDefaultTypeInternal; -extern PrepareRequestDefaultTypeInternal _PrepareRequest_default_instance_; -class PrepareResponse; -struct PrepareResponseDefaultTypeInternal; -extern PrepareResponseDefaultTypeInternal _PrepareResponse_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; @@ -151,12 +181,6 @@ extern ResetSettingsRequestDefaultTypeInternal _ResetSettingsRequest_default_ins class ResetSettingsResponse; struct ResetSettingsResponseDefaultTypeInternal; extern ResetSettingsResponseDefaultTypeInternal _ResetSettingsResponse_default_instance_; -class SelectCameraRequest; -struct SelectCameraRequestDefaultTypeInternal; -extern SelectCameraRequestDefaultTypeInternal _SelectCameraRequest_default_instance_; -class SelectCameraResponse; -struct SelectCameraResponseDefaultTypeInternal; -extern SelectCameraResponseDefaultTypeInternal _SelectCameraResponse_default_instance_; class SetModeRequest; struct SetModeRequestDefaultTypeInternal; extern SetModeRequestDefaultTypeInternal _SetModeRequest_default_instance_; @@ -217,15 +241,15 @@ extern StopVideoStreamingRequestDefaultTypeInternal _StopVideoStreamingRequest_d class StopVideoStreamingResponse; struct StopVideoStreamingResponseDefaultTypeInternal; extern StopVideoStreamingResponseDefaultTypeInternal _StopVideoStreamingResponse_default_instance_; +class SubscribeCameraListRequest; +struct SubscribeCameraListRequestDefaultTypeInternal; +extern SubscribeCameraListRequestDefaultTypeInternal _SubscribeCameraListRequest_default_instance_; class SubscribeCaptureInfoRequest; struct SubscribeCaptureInfoRequestDefaultTypeInternal; extern SubscribeCaptureInfoRequestDefaultTypeInternal _SubscribeCaptureInfoRequest_default_instance_; class SubscribeCurrentSettingsRequest; struct SubscribeCurrentSettingsRequestDefaultTypeInternal; extern SubscribeCurrentSettingsRequestDefaultTypeInternal _SubscribeCurrentSettingsRequest_default_instance_; -class SubscribeInformationRequest; -struct SubscribeInformationRequestDefaultTypeInternal; -extern SubscribeInformationRequestDefaultTypeInternal _SubscribeInformationRequest_default_instance_; class SubscribeModeRequest; struct SubscribeModeRequestDefaultTypeInternal; extern SubscribeModeRequestDefaultTypeInternal _SubscribeModeRequest_default_instance_; @@ -554,9 +578,10 @@ inline bool PhotosRange_Parse(absl::string_view name, PhotosRange* value) { // ------------------------------------------------------------------- class ZoomStopRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomStopRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomStopRequest) */ { public: inline ZoomStopRequest() : ZoomStopRequest(nullptr) {} + ~ZoomStopRequest() override; template explicit PROTOBUF_CONSTEXPR ZoomStopRequest(::google::protobuf::internal::ConstantInitialized); @@ -611,7 +636,7 @@ class ZoomStopRequest final : &_ZoomStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 55; friend void swap(ZoomStopRequest& a, ZoomStopRequest& b) { a.Swap(&b); @@ -640,15 +665,29 @@ class ZoomStopRequest final : ZoomStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ZoomStopRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ZoomStopRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ZoomStopRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomStopRequest& from) { + ZoomStopRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ZoomStopRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -660,16 +699,37 @@ class ZoomStopRequest final : ZoomStopRequest(::google::protobuf::Arena* arena, const ZoomStopRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomStopRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -684,8 +744,11 @@ class ZoomStopRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -748,7 +811,7 @@ class ZoomRangeRequest final : &_ZoomRangeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 57; friend void swap(ZoomRangeRequest& a, ZoomRangeRequest& b) { a.Swap(&b); @@ -821,9 +884,20 @@ class ZoomRangeRequest final : // accessors ------------------------------------------------------- enum : int { - kRangeFieldNumber = 1, + kCameraIdFieldNumber = 1, + kRangeFieldNumber = 2, }; - // float range = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // float range = 2; void clear_range() ; float range() const; void set_range(float value); @@ -839,7 +913,7 @@ class ZoomRangeRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -856,6 +930,7 @@ class ZoomRangeRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; float range_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -865,9 +940,10 @@ class ZoomRangeRequest final : };// ------------------------------------------------------------------- class ZoomOutStartRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomOutStartRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomOutStartRequest) */ { public: inline ZoomOutStartRequest() : ZoomOutStartRequest(nullptr) {} + ~ZoomOutStartRequest() override; template explicit PROTOBUF_CONSTEXPR ZoomOutStartRequest(::google::protobuf::internal::ConstantInitialized); @@ -922,7 +998,7 @@ class ZoomOutStartRequest final : &_ZoomOutStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 53; friend void swap(ZoomOutStartRequest& a, ZoomOutStartRequest& b) { a.Swap(&b); @@ -951,15 +1027,29 @@ class ZoomOutStartRequest final : ZoomOutStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ZoomOutStartRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ZoomOutStartRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ZoomOutStartRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomOutStartRequest& from) { + ZoomOutStartRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ZoomOutStartRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -971,16 +1061,37 @@ class ZoomOutStartRequest final : ZoomOutStartRequest(::google::protobuf::Arena* arena, const ZoomOutStartRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomOutStartRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -995,15 +1106,19 @@ class ZoomOutStartRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- class ZoomInStartRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomInStartRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomInStartRequest) */ { public: inline ZoomInStartRequest() : ZoomInStartRequest(nullptr) {} + ~ZoomInStartRequest() override; template explicit PROTOBUF_CONSTEXPR ZoomInStartRequest(::google::protobuf::internal::ConstantInitialized); @@ -1058,7 +1173,7 @@ class ZoomInStartRequest final : &_ZoomInStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 44; + 51; friend void swap(ZoomInStartRequest& a, ZoomInStartRequest& b) { a.Swap(&b); @@ -1087,15 +1202,29 @@ class ZoomInStartRequest final : ZoomInStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ZoomInStartRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ZoomInStartRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ZoomInStartRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomInStartRequest& from) { + ZoomInStartRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ZoomInStartRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -1107,16 +1236,37 @@ class ZoomInStartRequest final : ZoomInStartRequest(::google::protobuf::Arena* arena, const ZoomInStartRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomInStartRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1131,8 +1281,11 @@ class ZoomInStartRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -1195,7 +1348,7 @@ class VideoStreamSettings final : &_VideoStreamSettings_default_instance_); } static constexpr int kIndexInFileMessages = - 71; + 78; friend void swap(VideoStreamSettings& a, VideoStreamSettings& b) { a.Swap(&b); @@ -1390,9 +1543,10 @@ class VideoStreamSettings final : };// ------------------------------------------------------------------- class TrackStopRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TrackStopRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TrackStopRequest) */ { public: inline TrackStopRequest() : TrackStopRequest(nullptr) {} + ~TrackStopRequest() override; template explicit PROTOBUF_CONSTEXPR TrackStopRequest(::google::protobuf::internal::ConstantInitialized); @@ -1447,7 +1601,7 @@ class TrackStopRequest final : &_TrackStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 56; + 63; friend void swap(TrackStopRequest& a, TrackStopRequest& b) { a.Swap(&b); @@ -1476,15 +1630,29 @@ class TrackStopRequest final : TrackStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const TrackStopRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const TrackStopRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const TrackStopRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const TrackStopRequest& from) { + TrackStopRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(TrackStopRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -1496,16 +1664,37 @@ class TrackStopRequest final : TrackStopRequest(::google::protobuf::Arena* arena, const TrackStopRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TrackStopRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1520,8 +1709,11 @@ class TrackStopRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -1584,7 +1776,7 @@ class TrackRectangleRequest final : &_TrackRectangleRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 54; + 61; friend void swap(TrackRectangleRequest& a, TrackRectangleRequest& b) { a.Swap(&b); @@ -1657,12 +1849,23 @@ class TrackRectangleRequest final : // accessors ------------------------------------------------------- enum : int { - kTopLeftXFieldNumber = 1, - kTopLeftYFieldNumber = 2, - kBottomRightXFieldNumber = 3, - kBottomRightYFieldNumber = 4, + kCameraIdFieldNumber = 1, + kTopLeftXFieldNumber = 2, + kTopLeftYFieldNumber = 3, + kBottomRightXFieldNumber = 4, + kBottomRightYFieldNumber = 5, }; - // float top_left_x = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // float top_left_x = 2; void clear_top_left_x() ; float top_left_x() const; void set_top_left_x(float value); @@ -1672,7 +1875,7 @@ class TrackRectangleRequest final : void _internal_set_top_left_x(float value); public: - // float top_left_y = 2; + // float top_left_y = 3; void clear_top_left_y() ; float top_left_y() const; void set_top_left_y(float value); @@ -1682,7 +1885,7 @@ class TrackRectangleRequest final : void _internal_set_top_left_y(float value); public: - // float bottom_right_x = 3; + // float bottom_right_x = 4; void clear_bottom_right_x() ; float bottom_right_x() const; void set_bottom_right_x(float value); @@ -1692,7 +1895,7 @@ class TrackRectangleRequest final : void _internal_set_bottom_right_x(float value); public: - // float bottom_right_y = 4; + // float bottom_right_y = 5; void clear_bottom_right_y() ; float bottom_right_y() const; void set_bottom_right_y(float value); @@ -1708,7 +1911,7 @@ class TrackRectangleRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, + 3, 5, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -1725,6 +1928,7 @@ class TrackRectangleRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; float top_left_x_; float top_left_y_; float bottom_right_x_; @@ -1795,7 +1999,7 @@ class TrackPointRequest final : &_TrackPointRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 59; friend void swap(TrackPointRequest& a, TrackPointRequest& b) { a.Swap(&b); @@ -1868,11 +2072,22 @@ class TrackPointRequest final : // accessors ------------------------------------------------------- enum : int { - kPointXFieldNumber = 1, - kPointYFieldNumber = 2, - kRadiusFieldNumber = 3, + kCameraIdFieldNumber = 1, + kPointXFieldNumber = 2, + kPointYFieldNumber = 3, + kRadiusFieldNumber = 4, }; - // float point_x = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // float point_x = 2; void clear_point_x() ; float point_x() const; void set_point_x(float value); @@ -1882,7 +2097,7 @@ class TrackPointRequest final : void _internal_set_point_x(float value); public: - // float point_y = 2; + // float point_y = 3; void clear_point_y() ; float point_y() const; void set_point_y(float value); @@ -1892,7 +2107,7 @@ class TrackPointRequest final : void _internal_set_point_y(float value); public: - // float radius = 3; + // float radius = 4; void clear_radius() ; float radius() const; void set_radius(float value); @@ -1908,7 +2123,7 @@ class TrackPointRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -1925,6 +2140,7 @@ class TrackPointRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; float point_x_; float point_y_; float radius_; @@ -1936,9 +2152,10 @@ class TrackPointRequest final : };// ------------------------------------------------------------------- class TakePhotoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TakePhotoRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TakePhotoRequest) */ { public: inline TakePhotoRequest() : TakePhotoRequest(nullptr) {} + ~TakePhotoRequest() override; template explicit PROTOBUF_CONSTEXPR TakePhotoRequest(::google::protobuf::internal::ConstantInitialized); @@ -1993,7 +2210,7 @@ class TakePhotoRequest final : &_TakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 0; friend void swap(TakePhotoRequest& a, TakePhotoRequest& b) { a.Swap(&b); @@ -2022,19 +2239,33 @@ class TakePhotoRequest final : TakePhotoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const TakePhotoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const TakePhotoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const TakePhotoRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const TakePhotoRequest& from) { + TakePhotoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(TakePhotoRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.camera.TakePhotoRequest"; } protected: @@ -2042,16 +2273,37 @@ class TakePhotoRequest final : TakePhotoRequest(::google::protobuf::Arena* arena, const TakePhotoRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TakePhotoRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -2066,8 +2318,11 @@ class TakePhotoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -2129,7 +2384,7 @@ class SubscribeVideoStreamInfoRequest final : &_SubscribeVideoStreamInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 23; friend void swap(SubscribeVideoStreamInfoRequest& a, SubscribeVideoStreamInfoRequest& b) { a.Swap(&b); @@ -2265,7 +2520,7 @@ class SubscribeStatusRequest final : &_SubscribeStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 27; friend void swap(SubscribeStatusRequest& a, SubscribeStatusRequest& b) { a.Swap(&b); @@ -2401,7 +2656,7 @@ class SubscribePossibleSettingOptionsRequest final : &_SubscribePossibleSettingOptionsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 31; friend void swap(SubscribePossibleSettingOptionsRequest& a, SubscribePossibleSettingOptionsRequest& b) { a.Swap(&b); @@ -2537,7 +2792,7 @@ class SubscribeModeRequest final : &_SubscribeModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 21; friend void swap(SubscribeModeRequest& a, SubscribeModeRequest& b) { a.Swap(&b); @@ -2615,25 +2870,25 @@ class SubscribeModeRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeInformationRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeInformationRequest) */ { +class SubscribeCurrentSettingsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) */ { public: - inline SubscribeInformationRequest() : SubscribeInformationRequest(nullptr) {} + inline SubscribeCurrentSettingsRequest() : SubscribeCurrentSettingsRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeInformationRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeInformationRequest(const SubscribeInformationRequest& from) - : SubscribeInformationRequest(nullptr, from) {} - SubscribeInformationRequest(SubscribeInformationRequest&& from) noexcept - : SubscribeInformationRequest() { + inline SubscribeCurrentSettingsRequest(const SubscribeCurrentSettingsRequest& from) + : SubscribeCurrentSettingsRequest(nullptr, from) {} + SubscribeCurrentSettingsRequest(SubscribeCurrentSettingsRequest&& from) noexcept + : SubscribeCurrentSettingsRequest() { *this = ::std::move(from); } - inline SubscribeInformationRequest& operator=(const SubscribeInformationRequest& from) { + inline SubscribeCurrentSettingsRequest& operator=(const SubscribeCurrentSettingsRequest& from) { CopyFrom(from); return *this; } - inline SubscribeInformationRequest& operator=(SubscribeInformationRequest&& from) noexcept { + inline SubscribeCurrentSettingsRequest& operator=(SubscribeCurrentSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2665,20 +2920,20 @@ class SubscribeInformationRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeInformationRequest& default_instance() { + static const SubscribeCurrentSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeInformationRequest_default_instance_); + static inline const SubscribeCurrentSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCurrentSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 29; - friend void swap(SubscribeInformationRequest& a, SubscribeInformationRequest& b) { + friend void swap(SubscribeCurrentSettingsRequest& a, SubscribeCurrentSettingsRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeInformationRequest* other) { + inline void Swap(SubscribeCurrentSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2691,7 +2946,7 @@ class SubscribeInformationRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeInformationRequest* other) { + void UnsafeArenaSwap(SubscribeCurrentSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2699,15 +2954,15 @@ class SubscribeInformationRequest final : // implements Message ---------------------------------------------- - SubscribeInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeCurrentSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeInformationRequest& from) { + inline void CopyFrom(const SubscribeCurrentSettingsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeInformationRequest& from) { + void MergeFrom(const SubscribeCurrentSettingsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2715,11 +2970,11 @@ class SubscribeInformationRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeInformationRequest"; + return "mavsdk.rpc.camera.SubscribeCurrentSettingsRequest"; } protected: - explicit SubscribeInformationRequest(::google::protobuf::Arena* arena); - SubscribeInformationRequest(::google::protobuf::Arena* arena, const SubscribeInformationRequest& from); + explicit SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena); + SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena, const SubscribeCurrentSettingsRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2728,7 +2983,7 @@ class SubscribeInformationRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeInformationRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) private: class _Internal; @@ -2751,25 +3006,25 @@ class SubscribeInformationRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeCurrentSettingsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) */ { +class SubscribeCaptureInfoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) */ { public: - inline SubscribeCurrentSettingsRequest() : SubscribeCurrentSettingsRequest(nullptr) {} + inline SubscribeCaptureInfoRequest() : SubscribeCaptureInfoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCaptureInfoRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCurrentSettingsRequest(const SubscribeCurrentSettingsRequest& from) - : SubscribeCurrentSettingsRequest(nullptr, from) {} - SubscribeCurrentSettingsRequest(SubscribeCurrentSettingsRequest&& from) noexcept - : SubscribeCurrentSettingsRequest() { + inline SubscribeCaptureInfoRequest(const SubscribeCaptureInfoRequest& from) + : SubscribeCaptureInfoRequest(nullptr, from) {} + SubscribeCaptureInfoRequest(SubscribeCaptureInfoRequest&& from) noexcept + : SubscribeCaptureInfoRequest() { *this = ::std::move(from); } - inline SubscribeCurrentSettingsRequest& operator=(const SubscribeCurrentSettingsRequest& from) { + inline SubscribeCaptureInfoRequest& operator=(const SubscribeCaptureInfoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCurrentSettingsRequest& operator=(SubscribeCurrentSettingsRequest&& from) noexcept { + inline SubscribeCaptureInfoRequest& operator=(SubscribeCaptureInfoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2801,20 +3056,20 @@ class SubscribeCurrentSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCurrentSettingsRequest& default_instance() { + static const SubscribeCaptureInfoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCurrentSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCurrentSettingsRequest_default_instance_); + static inline const SubscribeCaptureInfoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCaptureInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 25; - friend void swap(SubscribeCurrentSettingsRequest& a, SubscribeCurrentSettingsRequest& b) { + friend void swap(SubscribeCaptureInfoRequest& a, SubscribeCaptureInfoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCurrentSettingsRequest* other) { + inline void Swap(SubscribeCaptureInfoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2827,7 +3082,7 @@ class SubscribeCurrentSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCurrentSettingsRequest* other) { + void UnsafeArenaSwap(SubscribeCaptureInfoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2835,15 +3090,15 @@ class SubscribeCurrentSettingsRequest final : // implements Message ---------------------------------------------- - SubscribeCurrentSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeCaptureInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCurrentSettingsRequest& from) { + inline void CopyFrom(const SubscribeCaptureInfoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCurrentSettingsRequest& from) { + void MergeFrom(const SubscribeCaptureInfoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2851,11 +3106,11 @@ class SubscribeCurrentSettingsRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeCurrentSettingsRequest"; + return "mavsdk.rpc.camera.SubscribeCaptureInfoRequest"; } protected: - explicit SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena); - SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena, const SubscribeCurrentSettingsRequest& from); + explicit SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena); + SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena, const SubscribeCaptureInfoRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2864,7 +3119,7 @@ class SubscribeCurrentSettingsRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) private: class _Internal; @@ -2887,25 +3142,25 @@ class SubscribeCurrentSettingsRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeCaptureInfoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) */ { +class SubscribeCameraListRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCameraListRequest) */ { public: - inline SubscribeCaptureInfoRequest() : SubscribeCaptureInfoRequest(nullptr) {} + inline SubscribeCameraListRequest() : SubscribeCameraListRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCaptureInfoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCameraListRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCaptureInfoRequest(const SubscribeCaptureInfoRequest& from) - : SubscribeCaptureInfoRequest(nullptr, from) {} - SubscribeCaptureInfoRequest(SubscribeCaptureInfoRequest&& from) noexcept - : SubscribeCaptureInfoRequest() { + inline SubscribeCameraListRequest(const SubscribeCameraListRequest& from) + : SubscribeCameraListRequest(nullptr, from) {} + SubscribeCameraListRequest(SubscribeCameraListRequest&& from) noexcept + : SubscribeCameraListRequest() { *this = ::std::move(from); } - inline SubscribeCaptureInfoRequest& operator=(const SubscribeCaptureInfoRequest& from) { + inline SubscribeCameraListRequest& operator=(const SubscribeCameraListRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCaptureInfoRequest& operator=(SubscribeCaptureInfoRequest&& from) noexcept { + inline SubscribeCameraListRequest& operator=(SubscribeCameraListRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2937,20 +3192,20 @@ class SubscribeCaptureInfoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCaptureInfoRequest& default_instance() { + static const SubscribeCameraListRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCaptureInfoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCaptureInfoRequest_default_instance_); + static inline const SubscribeCameraListRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCameraListRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 18; - friend void swap(SubscribeCaptureInfoRequest& a, SubscribeCaptureInfoRequest& b) { + friend void swap(SubscribeCameraListRequest& a, SubscribeCameraListRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCaptureInfoRequest* other) { + inline void Swap(SubscribeCameraListRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2963,7 +3218,7 @@ class SubscribeCaptureInfoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCaptureInfoRequest* other) { + void UnsafeArenaSwap(SubscribeCameraListRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2971,15 +3226,15 @@ class SubscribeCaptureInfoRequest final : // implements Message ---------------------------------------------- - SubscribeCaptureInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeCameraListRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCaptureInfoRequest& from) { + inline void CopyFrom(const SubscribeCameraListRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCaptureInfoRequest& from) { + void MergeFrom(const SubscribeCameraListRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2987,11 +3242,11 @@ class SubscribeCaptureInfoRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeCaptureInfoRequest"; + return "mavsdk.rpc.camera.SubscribeCameraListRequest"; } protected: - explicit SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena); - SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena, const SubscribeCaptureInfoRequest& from); + explicit SubscribeCameraListRequest(::google::protobuf::Arena* arena); + SubscribeCameraListRequest(::google::protobuf::Arena* arena, const SubscribeCameraListRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -3000,7 +3255,7 @@ class SubscribeCaptureInfoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCameraListRequest) private: class _Internal; @@ -3082,7 +3337,7 @@ class StopVideoStreamingRequest final : &_StopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 12; friend void swap(StopVideoStreamingRequest& a, StopVideoStreamingRequest& b) { a.Swap(&b); @@ -3155,9 +3410,20 @@ class StopVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kStreamIdFieldNumber = 1, + kCameraIdFieldNumber = 1, + kStreamIdFieldNumber = 2, }; - // int32 stream_id = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // int32 stream_id = 2; void clear_stream_id() ; ::int32_t stream_id() const; void set_stream_id(::int32_t value); @@ -3173,7 +3439,7 @@ class StopVideoStreamingRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -3190,6 +3456,7 @@ class StopVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -3199,9 +3466,10 @@ class StopVideoStreamingRequest final : };// ------------------------------------------------------------------- class StopVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoRequest) */ { public: inline StopVideoRequest() : StopVideoRequest(nullptr) {} + ~StopVideoRequest() override; template explicit PROTOBUF_CONSTEXPR StopVideoRequest(::google::protobuf::internal::ConstantInitialized); @@ -3256,7 +3524,7 @@ class StopVideoRequest final : &_StopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 8; friend void swap(StopVideoRequest& a, StopVideoRequest& b) { a.Swap(&b); @@ -3285,15 +3553,29 @@ class StopVideoRequest final : StopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StopVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StopVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StopVideoRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StopVideoRequest& from) { + StopVideoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(StopVideoRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -3305,16 +3587,37 @@ class StopVideoRequest final : StopVideoRequest(::google::protobuf::Arena* arena, const StopVideoRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopVideoRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3329,15 +3632,19 @@ class StopVideoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- class StopPhotoIntervalRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopPhotoIntervalRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopPhotoIntervalRequest) */ { public: inline StopPhotoIntervalRequest() : StopPhotoIntervalRequest(nullptr) {} + ~StopPhotoIntervalRequest() override; template explicit PROTOBUF_CONSTEXPR StopPhotoIntervalRequest(::google::protobuf::internal::ConstantInitialized); @@ -3392,7 +3699,7 @@ class StopPhotoIntervalRequest final : &_StopPhotoIntervalRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 4; friend void swap(StopPhotoIntervalRequest& a, StopPhotoIntervalRequest& b) { a.Swap(&b); @@ -3421,15 +3728,29 @@ class StopPhotoIntervalRequest final : StopPhotoIntervalRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StopPhotoIntervalRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StopPhotoIntervalRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StopPhotoIntervalRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StopPhotoIntervalRequest& from) { + StopPhotoIntervalRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(StopPhotoIntervalRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -3441,16 +3762,37 @@ class StopPhotoIntervalRequest final : StopPhotoIntervalRequest(::google::protobuf::Arena* arena, const StopPhotoIntervalRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopPhotoIntervalRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -3465,8 +3807,11 @@ class StopPhotoIntervalRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -3529,7 +3874,7 @@ class Status final : &_Status_default_instance_); } static constexpr int kIndexInFileMessages = - 73; + 80; friend void swap(Status& a, Status& b) { a.Swap(&b); @@ -3648,18 +3993,19 @@ class Status final : // accessors ------------------------------------------------------- enum : int { - kMediaFolderNameFieldNumber = 7, - kVideoOnFieldNumber = 1, - kPhotoIntervalOnFieldNumber = 2, - kUsedStorageMibFieldNumber = 3, - kAvailableStorageMibFieldNumber = 4, - kTotalStorageMibFieldNumber = 5, - kRecordingTimeSFieldNumber = 6, - kStorageStatusFieldNumber = 8, - kStorageIdFieldNumber = 9, - kStorageTypeFieldNumber = 10, + kMediaFolderNameFieldNumber = 8, + kCameraIdFieldNumber = 1, + kVideoOnFieldNumber = 2, + kPhotoIntervalOnFieldNumber = 3, + kUsedStorageMibFieldNumber = 4, + kAvailableStorageMibFieldNumber = 5, + kTotalStorageMibFieldNumber = 6, + kRecordingTimeSFieldNumber = 7, + kStorageStatusFieldNumber = 9, + kStorageIdFieldNumber = 10, + kStorageTypeFieldNumber = 11, }; - // string media_folder_name = 7; + // string media_folder_name = 8; void clear_media_folder_name() ; const std::string& media_folder_name() const; template @@ -3675,7 +4021,17 @@ class Status final : std::string* _internal_mutable_media_folder_name(); public: - // bool video_on = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // bool video_on = 2; void clear_video_on() ; bool video_on() const; void set_video_on(bool value); @@ -3685,7 +4041,7 @@ class Status final : void _internal_set_video_on(bool value); public: - // bool photo_interval_on = 2; + // bool photo_interval_on = 3; void clear_photo_interval_on() ; bool photo_interval_on() const; void set_photo_interval_on(bool value); @@ -3695,7 +4051,7 @@ class Status final : void _internal_set_photo_interval_on(bool value); public: - // float used_storage_mib = 3; + // float used_storage_mib = 4; void clear_used_storage_mib() ; float used_storage_mib() const; void set_used_storage_mib(float value); @@ -3705,7 +4061,7 @@ class Status final : void _internal_set_used_storage_mib(float value); public: - // float available_storage_mib = 4; + // float available_storage_mib = 5; void clear_available_storage_mib() ; float available_storage_mib() const; void set_available_storage_mib(float value); @@ -3715,7 +4071,7 @@ class Status final : void _internal_set_available_storage_mib(float value); public: - // float total_storage_mib = 5; + // float total_storage_mib = 6; void clear_total_storage_mib() ; float total_storage_mib() const; void set_total_storage_mib(float value); @@ -3725,7 +4081,7 @@ class Status final : void _internal_set_total_storage_mib(float value); public: - // float recording_time_s = 6; + // float recording_time_s = 7; void clear_recording_time_s() ; float recording_time_s() const; void set_recording_time_s(float value); @@ -3735,7 +4091,7 @@ class Status final : void _internal_set_recording_time_s(float value); public: - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 9; void clear_storage_status() ; ::mavsdk::rpc::camera::Status_StorageStatus storage_status() const; void set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); @@ -3745,7 +4101,7 @@ class Status final : void _internal_set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); public: - // uint32 storage_id = 9; + // uint32 storage_id = 10; void clear_storage_id() ; ::uint32_t storage_id() const; void set_storage_id(::uint32_t value); @@ -3755,7 +4111,7 @@ class Status final : void _internal_set_storage_id(::uint32_t value); public: - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + // .mavsdk.rpc.camera.Status.StorageType storage_type = 11; void clear_storage_type() ; ::mavsdk::rpc::camera::Status_StorageType storage_type() const; void set_storage_type(::mavsdk::rpc::camera::Status_StorageType value); @@ -3771,7 +4127,7 @@ class Status final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 4, 10, 0, + 4, 11, 0, 58, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -3789,6 +4145,7 @@ class Status final : inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::ArenaStringPtr media_folder_name_; + ::int32_t camera_id_; bool video_on_; bool photo_interval_on_; float used_storage_mib_; @@ -3864,7 +4221,7 @@ class StartVideoStreamingRequest final : &_StartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 10; friend void swap(StartVideoStreamingRequest& a, StartVideoStreamingRequest& b) { a.Swap(&b); @@ -3937,9 +4294,20 @@ class StartVideoStreamingRequest final : // accessors ------------------------------------------------------- enum : int { - kStreamIdFieldNumber = 1, + kCameraIdFieldNumber = 1, + kStreamIdFieldNumber = 2, }; - // int32 stream_id = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // int32 stream_id = 2; void clear_stream_id() ; ::int32_t stream_id() const; void set_stream_id(::int32_t value); @@ -3955,7 +4323,7 @@ class StartVideoStreamingRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -3972,6 +4340,7 @@ class StartVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -3981,9 +4350,10 @@ class StartVideoStreamingRequest final : };// ------------------------------------------------------------------- class StartVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoRequest) */ { public: inline StartVideoRequest() : StartVideoRequest(nullptr) {} + ~StartVideoRequest() override; template explicit PROTOBUF_CONSTEXPR StartVideoRequest(::google::protobuf::internal::ConstantInitialized); @@ -4038,7 +4408,7 @@ class StartVideoRequest final : &_StartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 6; friend void swap(StartVideoRequest& a, StartVideoRequest& b) { a.Swap(&b); @@ -4067,15 +4437,29 @@ class StartVideoRequest final : StartVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StartVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StartVideoRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StartVideoRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StartVideoRequest& from) { + StartVideoRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(StartVideoRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -4087,16 +4471,37 @@ class StartVideoRequest final : StartVideoRequest(::google::protobuf::Arena* arena, const StartVideoRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kCameraIdFieldNumber = 1, + }; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -4111,8 +4516,11 @@ class StartVideoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- @@ -4175,7 +4583,7 @@ class StartPhotoIntervalRequest final : &_StartPhotoIntervalRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 2; friend void swap(StartPhotoIntervalRequest& a, StartPhotoIntervalRequest& b) { a.Swap(&b); @@ -4248,9 +4656,20 @@ class StartPhotoIntervalRequest final : // accessors ------------------------------------------------------- enum : int { - kIntervalSFieldNumber = 1, + kCameraIdFieldNumber = 1, + kIntervalSFieldNumber = 2, }; - // float interval_s = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // float interval_s = 2; void clear_interval_s() ; float interval_s() const; void set_interval_s(float value); @@ -4266,7 +4685,7 @@ class StartPhotoIntervalRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -4283,6 +4702,7 @@ class StartPhotoIntervalRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; float interval_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -4350,7 +4770,7 @@ class SetModeRequest final : &_SetModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 14; friend void swap(SetModeRequest& a, SetModeRequest& b) { a.Swap(&b); @@ -4423,9 +4843,20 @@ class SetModeRequest final : // accessors ------------------------------------------------------- enum : int { - kModeFieldNumber = 1, + kCameraIdFieldNumber = 1, + kModeFieldNumber = 2, }; - // .mavsdk.rpc.camera.Mode mode = 1; + // int32 camera_id = 1; + void clear_camera_id() ; + ::int32_t camera_id() const; + void set_camera_id(::int32_t value); + + private: + ::int32_t _internal_camera_id() const; + void _internal_set_camera_id(::int32_t value); + + public: + // .mavsdk.rpc.camera.Mode mode = 2; void clear_mode() ; ::mavsdk::rpc::camera::Mode mode() const; void set_mode(::mavsdk::rpc::camera::Mode value); @@ -4441,7 +4872,7 @@ class SetModeRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -4458,6 +4889,7 @@ class SetModeRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t camera_id_; int mode_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -4466,26 +4898,26 @@ class SetModeRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SelectCameraRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SelectCameraRequest) */ { +class ResetSettingsRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ResetSettingsRequest) */ { public: - inline SelectCameraRequest() : SelectCameraRequest(nullptr) {} - ~SelectCameraRequest() override; + inline ResetSettingsRequest() : ResetSettingsRequest(nullptr) {} + ~ResetSettingsRequest() override; template - explicit PROTOBUF_CONSTEXPR SelectCameraRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); - inline SelectCameraRequest(const SelectCameraRequest& from) - : SelectCameraRequest(nullptr, from) {} - SelectCameraRequest(SelectCameraRequest&& from) noexcept - : SelectCameraRequest() { + inline ResetSettingsRequest(const ResetSettingsRequest& from) + : ResetSettingsRequest(nullptr, from) {} + ResetSettingsRequest(ResetSettingsRequest&& from) noexcept + : ResetSettingsRequest() { *this = ::std::move(from); } - inline SelectCameraRequest& operator=(const SelectCameraRequest& from) { + inline ResetSettingsRequest& operator=(const ResetSettingsRequest& from) { CopyFrom(from); return *this; } - inline SelectCameraRequest& operator=(SelectCameraRequest&& from) noexcept { + inline ResetSettingsRequest& operator=(ResetSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4517,20 +4949,20 @@ class SelectCameraRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SelectCameraRequest& default_instance() { + static const ResetSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const SelectCameraRequest* internal_default_instance() { - return reinterpret_cast( - &_SelectCameraRequest_default_instance_); + static inline const ResetSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_ResetSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 41; + 49; - friend void swap(SelectCameraRequest& a, SelectCameraRequest& b) { + friend void swap(ResetSettingsRequest& a, ResetSettingsRequest& b) { a.Swap(&b); } - inline void Swap(SelectCameraRequest* other) { + inline void Swap(ResetSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4543,7 +4975,7 @@ class SelectCameraRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SelectCameraRequest* other) { + void UnsafeArenaSwap(ResetSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4551,14 +4983,14 @@ class SelectCameraRequest final : // implements Message ---------------------------------------------- - SelectCameraRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SelectCameraRequest& from); + void CopyFrom(const ResetSettingsRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SelectCameraRequest& from) { - SelectCameraRequest::MergeImpl(*this, from); + void MergeFrom( const ResetSettingsRequest& from) { + ResetSettingsRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4576,16 +5008,16 @@ class SelectCameraRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SelectCameraRequest* other); + void InternalSwap(ResetSettingsRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SelectCameraRequest"; + return "mavsdk.rpc.camera.ResetSettingsRequest"; } protected: - explicit SelectCameraRequest(::google::protobuf::Arena* arena); - SelectCameraRequest(::google::protobuf::Arena* arena, const SelectCameraRequest& from); + explicit ResetSettingsRequest(::google::protobuf::Arena* arena); + ResetSettingsRequest(::google::protobuf::Arena* arena, const ResetSettingsRequest& from); public: static const ClassData _class_data_; @@ -4610,7 +5042,7 @@ class SelectCameraRequest final : void _internal_set_camera_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SelectCameraRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ResetSettingsRequest) private: class _Internal; @@ -4641,25 +5073,26 @@ class SelectCameraRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class ResetSettingsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ResetSettingsRequest) */ { +class Quaternion final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Quaternion) */ { public: - inline ResetSettingsRequest() : ResetSettingsRequest(nullptr) {} + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; template - explicit PROTOBUF_CONSTEXPR ResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); - inline ResetSettingsRequest(const ResetSettingsRequest& from) - : ResetSettingsRequest(nullptr, from) {} - ResetSettingsRequest(ResetSettingsRequest&& from) noexcept - : ResetSettingsRequest() { + inline Quaternion(const Quaternion& from) + : Quaternion(nullptr, from) {} + Quaternion(Quaternion&& from) noexcept + : Quaternion() { *this = ::std::move(from); } - inline ResetSettingsRequest& operator=(const ResetSettingsRequest& from) { + inline Quaternion& operator=(const Quaternion& from) { CopyFrom(from); return *this; } - inline ResetSettingsRequest& operator=(ResetSettingsRequest&& from) noexcept { + inline Quaternion& operator=(Quaternion&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4691,20 +5124,20 @@ class ResetSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ResetSettingsRequest& default_instance() { + static const Quaternion& default_instance() { return *internal_default_instance(); } - static inline const ResetSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_ResetSettingsRequest_default_instance_); + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 75; - friend void swap(ResetSettingsRequest& a, ResetSettingsRequest& b) { + friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); } - inline void Swap(ResetSettingsRequest* other) { + inline void Swap(Quaternion* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4717,7 +5150,7 @@ class ResetSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ResetSettingsRequest* other) { + void UnsafeArenaSwap(Quaternion* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4725,78 +5158,152 @@ class ResetSettingsRequest final : // implements Message ---------------------------------------------- - ResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ResetSettingsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ResetSettingsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const Quaternion& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const Quaternion& from) { + Quaternion::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(Quaternion* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.ResetSettingsRequest"; + return "mavsdk.rpc.camera.Quaternion"; } protected: - explicit ResetSettingsRequest(::google::protobuf::Arena* arena); - ResetSettingsRequest(::google::protobuf::Arena* arena, const ResetSettingsRequest& from); + explicit Quaternion(::google::protobuf::Arena* arena); + Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ResetSettingsRequest) - private: - class _Internal; + enum : int { + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 4, + }; + // float w = 1; + void clear_w() ; + float w() const; + void set_w(float value); - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { + private: + float _internal_w() const; + void _internal_set_w(float value); - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - PROTOBUF_TSAN_DECLARE_MEMBER - }; - friend struct ::TableStruct_camera_2fcamera_2eproto; -};// ------------------------------------------------------------------- + public: + // float x = 2; + void clear_x() ; + float x() const; + void set_x(float value); -class Quaternion final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Quaternion) */ { + private: + float _internal_x() const; + void _internal_set_x(float value); + + public: + // float y = 3; + void clear_y() ; + float y() const; + void set_y(float value); + + private: + float _internal_y() const; + void _internal_set_y(float value); + + public: + // float z = 4; + void clear_z() ; + float z() const; + void set_z(float value); + + private: + float _internal_z() const; + void _internal_set_z(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Quaternion) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 4, 0, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + float w_; + float x_; + float y_; + float z_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_camera_2fcamera_2eproto; +};// ------------------------------------------------------------------- + +class Position final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Position) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline Position() : Position(nullptr) {} + ~Position() override; template - explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); - inline Quaternion(const Quaternion& from) - : Quaternion(nullptr, from) {} - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + inline Position(const Position& from) + : Position(nullptr, from) {} + Position(Position&& from) noexcept + : Position() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline Position& operator=(const Position& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline Position& operator=(Position&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4828,20 +5335,20 @@ class Quaternion final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const Position& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 68; + 74; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(Position& a, Position& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(Position* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4854,7 +5361,7 @@ class Quaternion final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(Position* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4862,14 +5369,14 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Position* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const Position& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const Position& from) { + Position::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4887,16 +5394,16 @@ class Quaternion final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Quaternion* other); + void InternalSwap(Position* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.Quaternion"; + return "mavsdk.rpc.camera.Position"; } protected: - explicit Quaternion(::google::protobuf::Arena* arena); - Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); + explicit Position(::google::protobuf::Arena* arena); + Position(::google::protobuf::Arena* arena, const Position& from); public: static const ClassData _class_data_; @@ -4909,52 +5416,52 @@ class Quaternion final : // accessors ------------------------------------------------------- enum : int { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 4, }; - // float w = 1; - void clear_w() ; - float w() const; - void set_w(float value); + // double latitude_deg = 1; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); private: - float _internal_w() const; - void _internal_set_w(float value); + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); public: - // float x = 2; - void clear_x() ; - float x() const; - void set_x(float value); + // double longitude_deg = 2; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); private: - float _internal_x() const; - void _internal_set_x(float value); + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); public: - // float y = 3; - void clear_y() ; - float y() const; - void set_y(float value); + // float absolute_altitude_m = 3; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); private: - float _internal_y() const; - void _internal_set_y(float value); + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); public: - // float z = 4; - void clear_z() ; - float z() const; - void set_z(float value); + // float relative_altitude_m = 4; + void clear_relative_altitude_m() ; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); private: - float _internal_z() const; - void _internal_set_z(float value); + float _internal_relative_altitude_m() const; + void _internal_set_relative_altitude_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Position) private: class _Internal; @@ -4977,10 +5484,10 @@ class Quaternion final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float w_; - float x_; - float y_; - float z_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4988,25 +5495,26 @@ class Quaternion final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class PrepareRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.PrepareRequest) */ { +class Option final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Option) */ { public: - inline PrepareRequest() : PrepareRequest(nullptr) {} + inline Option() : Option(nullptr) {} + ~Option() override; template - explicit PROTOBUF_CONSTEXPR PrepareRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Option(::google::protobuf::internal::ConstantInitialized); - inline PrepareRequest(const PrepareRequest& from) - : PrepareRequest(nullptr, from) {} - PrepareRequest(PrepareRequest&& from) noexcept - : PrepareRequest() { + inline Option(const Option& from) + : Option(nullptr, from) {} + Option(Option&& from) noexcept + : Option() { *this = ::std::move(from); } - inline PrepareRequest& operator=(const PrepareRequest& from) { + inline Option& operator=(const Option& from) { CopyFrom(from); return *this; } - inline PrepareRequest& operator=(PrepareRequest&& from) noexcept { + inline Option& operator=(Option&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5038,20 +5546,20 @@ class PrepareRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PrepareRequest& default_instance() { + static const Option& default_instance() { return *internal_default_instance(); } - static inline const PrepareRequest* internal_default_instance() { - return reinterpret_cast( - &_PrepareRequest_default_instance_); + static inline const Option* internal_default_instance() { + return reinterpret_cast( + &_Option_default_instance_); } static constexpr int kIndexInFileMessages = - 0; + 81; - friend void swap(PrepareRequest& a, PrepareRequest& b) { + friend void swap(Option& a, Option& b) { a.Swap(&b); } - inline void Swap(PrepareRequest* other) { + inline void Swap(Option* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5064,7 +5572,7 @@ class PrepareRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PrepareRequest* other) { + void UnsafeArenaSwap(Option* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5072,78 +5580,140 @@ class PrepareRequest final : // implements Message ---------------------------------------------- - PrepareRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const PrepareRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + Option* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage