From 9da07e89c1d31b38671f62a9028c68f618142ea4 Mon Sep 17 00:00:00 2001 From: Pannapat Chirathanyanon Date: Tue, 27 Jun 2023 14:08:01 +0700 Subject: [PATCH 1/2] feature zoom focus tracking Signed-off-by: Julian Oes --- proto | 2 +- src/mavsdk/plugins/camera/camera.cpp | 117 + src/mavsdk/plugins/camera/camera_impl.cpp | 364 + src/mavsdk/plugins/camera/camera_impl.h | 45 + .../camera/include/plugins/camera/camera.h | 183 + src/mavsdk/plugins/camera/mocks/camera_mock.h | 12 + .../src/generated/camera/camera.grpc.pb.cc | 462 + .../src/generated/camera/camera.grpc.pb.h | 2221 ++- .../src/generated/camera/camera.pb.cc | 4934 +++++- .../src/generated/camera/camera.pb.h | 13612 +++++++++++----- .../src/plugins/camera/camera_service_impl.h | 278 + 11 files changed, 17375 insertions(+), 4855 deletions(-) diff --git a/proto b/proto index 1340df7ec1..211476a2a2 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 1340df7ec15c9f8ca8818b903161d353ad9d78ec +Subproject commit 211476a2a28dcb2e3fa534d7e8c4fb434e4e6a86 diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index e7e9126d57..89555b6117 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -264,6 +264,123 @@ Camera::Result Camera::reset_settings() const return _impl->reset_settings(); } +void Camera::zoom_in_start_async(const ResultCallback callback) +{ + _impl->zoom_in_start_async(callback); +} + +Camera::Result Camera::zoom_in_start() const +{ + return _impl->zoom_in_start(); +} + +void Camera::zoom_out_start_async(const ResultCallback callback) +{ + _impl->zoom_out_start_async(callback); +} + +Camera::Result Camera::zoom_out_start() const +{ + return _impl->zoom_out_start(); +} + +void Camera::zoom_stop_async(const ResultCallback callback) +{ + _impl->zoom_stop_async(callback); +} + +Camera::Result Camera::zoom_stop() const +{ + return _impl->zoom_stop(); +} + +void Camera::zoom_range_async(float range, const ResultCallback callback) +{ + _impl->zoom_range_async(range, callback); +} + +Camera::Result Camera::zoom_range(float range) const +{ + return _impl->zoom_range(range); +} + +void Camera::track_point_async( + float point_x, float point_y, float radius, const ResultCallback callback) +{ + _impl->track_point_async(point_x, point_y, radius, callback); +} + +Camera::Result Camera::track_point(float point_x, float point_y, float radius) const +{ + return _impl->track_point(point_x, point_y, radius); +} + +void Camera::track_rectangle_async( + 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); +} + +Camera::Result Camera::track_rectangle( + float top_left_x, float top_left_y, float bottom_right_x, float bottom_right_y) const +{ + return _impl->track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y); +} + +void Camera::track_stop_async(const ResultCallback callback) +{ + _impl->track_stop_async(callback); +} + +Camera::Result Camera::track_stop() const +{ + return _impl->track_stop(); +} + +void Camera::focus_in_start_async(const ResultCallback callback) +{ + _impl->focus_in_start_async(callback); +} + +Camera::Result Camera::focus_in_start() const +{ + return _impl->focus_in_start(); +} + +void Camera::focus_out_start_async(const ResultCallback callback) +{ + _impl->focus_out_start_async(callback); +} + +Camera::Result Camera::focus_out_start() const +{ + return _impl->focus_out_start(); +} + +void Camera::focus_stop_async(const ResultCallback callback) +{ + _impl->focus_stop_async(callback); +} + +Camera::Result Camera::focus_stop() const +{ + return _impl->focus_stop(); +} + +void Camera::focus_range_async(float range, const ResultCallback callback) +{ + _impl->focus_range_async(range, callback); +} + +Camera::Result Camera::focus_range(float range) const +{ + return _impl->focus_range(range); +} + std::ostream& operator<<(std::ostream& str, Camera::Result const& result) { switch (result) { diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index e7a9d250d1..712a750993 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -6,6 +6,7 @@ #include "unused.h" #include "callback_list.tpp" +#include #include #include #include @@ -320,6 +321,131 @@ CameraImpl::make_command_take_photo(float interval_s, float no_of_photos) return cmd_take_photo; } +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out() +{ + 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; + + return cmd; +} + +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in() +{ + 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; + + return cmd; +} + +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop() +{ + 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; + + return cmd; +} + +MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_range(float range) +{ + // Clip to safe range. + range = std::max(0.f, std::min(range, 100.f)); + + MavlinkCommandSender::CommandLong cmd{}; + 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; + + return cmd; +} + +MavlinkCommandSender::CommandLong +CameraImpl::make_command_track_point(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; + + 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) +{ + MavlinkCommandSender::CommandLong cmd{}; + cmd.command = MAV_CMD_CAMERA_TRACK_RECTANGLE; + cmd.params.maybe_param1 = top_left_x; + 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; + + return cmd; +} +MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop() +{ + MavlinkCommandSender::CommandLong cmd{}; + cmd.command = MAV_CMD_CAMERA_STOP_TRACKING; + cmd.target_component_id = _camera_id + MAV_COMP_ID_CAMERA; + + return cmd; +} +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in() +{ + 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; + + return cmd; +} +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out() +{ + 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; + + return cmd; +} +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop() +{ + 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; + + return cmd; +} +MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_range(float range) +{ + // Clip to safe range. + range = std::max(0.f, std::min(range, 100.f)); + + MavlinkCommandSender::CommandLong cmd{}; + 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; + + return cmd; +} + MavlinkCommandSender::CommandLong CameraImpl::make_command_stop_photo() { MavlinkCommandSender::CommandLong cmd_stop_photo{}; @@ -469,6 +595,106 @@ Camera::Result CameraImpl::take_photo() return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo)); } +Camera::Result CameraImpl::zoom_out_start() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_out(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::zoom_in_start() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_in(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::zoom_stop() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_stop(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::zoom_range(float range) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_range(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) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_track_point(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) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_track_rectangle(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() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_track_stop(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::focus_in_start() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_in(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::focus_out_start() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_out(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::focus_stop() +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_stop(); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + +Camera::Result CameraImpl::focus_range(float range) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_range(range); + + return camera_result_from_command_result(_system_impl->send_command(cmd)); +} + Camera::Result CameraImpl::start_photo_interval(float interval_s) { if (!interval_valid(interval_s)) { @@ -514,6 +740,144 @@ 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) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_in(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::zoom_out_start_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_out(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::zoom_stop_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_stop(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::zoom_range_async(float range, const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_zoom_range(range); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::track_point_async( + 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); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::track_rectangle_async( + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y, + const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_track_rectangle(top_left_x, top_left_y, bottom_right_x, bottom_right_y); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::track_stop_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_track_stop(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::focus_in_start_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_in(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::focus_out_start_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_out(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::focus_stop_async(const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_stop(); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + +void CameraImpl::focus_range_async(float range, const Camera::ResultCallback& callback) +{ + std::lock_guard lock(_capture.mutex); + + auto cmd = make_command_focus_range(range); + + _system_impl->send_command_async( + cmd, [this, callback](MavlinkCommandSender::Result result, float) { + receive_command_result(result, callback); + }); +} + void CameraImpl::take_photo_async(const Camera::ResultCallback& callback) { // TODO: check whether we are in photo mode. diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 8ff928d65f..3e398d4d24 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -34,6 +34,37 @@ class CameraImpl : public PluginImplBase { Camera::Result start_video(); Camera::Result stop_video(); + 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); + void track_rectangle_async( + 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 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); @@ -205,6 +236,20 @@ class CameraImpl : public PluginImplBase { MavlinkCommandSender::CommandLong make_command_request_video_stream_info(); MavlinkCommandSender::CommandLong make_command_request_video_stream_status(); + 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_track_point(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); + void request_missing_capture_info(); std::unique_ptr _camera_definition{}; diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 57bdaa5937..27b6bc68e0 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -919,6 +919,189 @@ class Camera : public PluginBase { */ Result reset_settings() 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); + + /** + * @brief Start zooming in. + * + * This function is blocking. See 'zoom_in_start_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result zoom_in_start() 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); + + /** + * @brief Start zooming out. + * + * This function is blocking. See 'zoom_out_start_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result zoom_out_start() const; + + /** + * @brief Stop zooming. + * + * This function is non-blocking. See 'zoom_stop' for the blocking counterpart. + */ + void zoom_stop_async(const ResultCallback callback); + + /** + * @brief Stop zooming. + * + * This function is blocking. See 'zoom_stop_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result zoom_stop() 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); + + /** + * @brief Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + * + * This function is blocking. See 'zoom_range_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result zoom_range(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); + + /** + * @brief Track point. + * + * This function is blocking. See 'track_point_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result track_point(float point_x, float point_y, float radius) const; + + /** + * @brief Track rectangle. + * + * This function is non-blocking. See 'track_rectangle' for the blocking counterpart. + */ + void track_rectangle_async( + float top_left_x, + float top_left_y, + float bottom_right_x, + float bottom_right_y, + const ResultCallback callback); + + /** + * @brief Track rectangle. + * + * This function is blocking. See 'track_rectangle_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result track_rectangle( + 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); + + /** + * @brief Stop tracking. + * + * This function is blocking. See 'track_stop_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result track_stop() 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); + + /** + * @brief Start focusing in. + * + * This function is blocking. See 'focus_in_start_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result focus_in_start() 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); + + /** + * @brief Start focusing out. + * + * This function is blocking. See 'focus_out_start_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result focus_out_start() const; + + /** + * @brief Stop focus. + * + * This function is non-blocking. See 'focus_stop' for the blocking counterpart. + */ + void focus_stop_async(const ResultCallback callback); + + /** + * @brief Stop focus. + * + * This function is blocking. See 'focus_stop_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result focus_stop() 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); + + /** + * @brief Focus with range value of full range (value between 0.0 and 100.0). + * + * This function is blocking. See 'focus_range_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result focus_range(float range) const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/camera/mocks/camera_mock.h b/src/mavsdk/plugins/camera/mocks/camera_mock.h index fbfbc920c1..c0b7ea0380 100644 --- a/src/mavsdk/plugins/camera/mocks/camera_mock.h +++ b/src/mavsdk/plugins/camera/mocks/camera_mock.h @@ -50,6 +50,18 @@ class MockCamera { std::pair>(Camera::PhotosRange)){}; MOCK_CONST_METHOD1(select_camera, Camera::Result(int32_t)){}; MOCK_CONST_METHOD0(reset_settings, Camera::Result()){}; + + MOCK_CONST_METHOD0(zoom_in_start, Camera::Result()){}; + MOCK_CONST_METHOD0(zoom_out_start, Camera::Result()){}; + MOCK_CONST_METHOD0(zoom_stop, Camera::Result()){}; + MOCK_CONST_METHOD1(zoom_range, Camera::Result(float)){}; + MOCK_CONST_METHOD3(track_point, Camera::Result(float, float, float)){}; + MOCK_CONST_METHOD4(track_rectangle, Camera::Result(float, float, float, float)){}; + MOCK_CONST_METHOD0(track_stop, Camera::Result()){}; + MOCK_CONST_METHOD0(focus_in_start, Camera::Result()){}; + MOCK_CONST_METHOD0(focus_out_start, Camera::Result()){}; + MOCK_CONST_METHOD0(focus_stop, Camera::Result()){}; + MOCK_CONST_METHOD1(focus_range, Camera::Result(float)){}; }; } // namespace testing 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 ebbb967ff2..b7106f8131 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.cc @@ -46,6 +46,17 @@ static const char* CameraService_method_names[] = { "/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", + "/mavsdk.rpc.camera.CameraService/ZoomStop", + "/mavsdk.rpc.camera.CameraService/ZoomRange", + "/mavsdk.rpc.camera.CameraService/TrackPoint", + "/mavsdk.rpc.camera.CameraService/TrackRectangle", + "/mavsdk.rpc.camera.CameraService/TrackStop", + "/mavsdk.rpc.camera.CameraService/FocusInStart", + "/mavsdk.rpc.camera.CameraService/FocusOutStart", + "/mavsdk.rpc.camera.CameraService/FocusStop", + "/mavsdk.rpc.camera.CameraService/FocusRange", }; std::unique_ptr< CameraService::Stub> CameraService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -77,6 +88,17 @@ CameraService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& chan , 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) {} ::grpc::Status CameraService::Stub::Prepare(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::PrepareRequest& request, ::mavsdk::rpc::camera::PrepareResponse* response) { @@ -536,6 +558,259 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse> return result; } +::grpc::Status CameraService::Stub::ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::mavsdk::rpc::camera::ZoomInStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ZoomInStart_, context, request, response); +} + +void CameraService::Stub::async::ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomInStart_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomInStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>* CameraService::Stub::PrepareAsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::ZoomInStartResponse, ::mavsdk::rpc::camera::ZoomInStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ZoomInStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>* CameraService::Stub::AsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncZoomInStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ZoomOutStart_, context, request, response); +} + +void CameraService::Stub::async::ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomOutStart_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomOutStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>* CameraService::Stub::PrepareAsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::ZoomOutStartResponse, ::mavsdk::rpc::camera::ZoomOutStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ZoomOutStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>* CameraService::Stub::AsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncZoomOutStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::mavsdk::rpc::camera::ZoomStopResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ZoomStop_, context, request, response); +} + +void CameraService::Stub::async::ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomStop_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomStop_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>* CameraService::Stub::PrepareAsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::ZoomStopResponse, ::mavsdk::rpc::camera::ZoomStopRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ZoomStop_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>* CameraService::Stub::AsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncZoomStopRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::mavsdk::rpc::camera::ZoomRangeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_ZoomRange_, context, request, response); +} + +void CameraService::Stub::async::ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomRange_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_ZoomRange_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>* CameraService::Stub::PrepareAsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::ZoomRangeResponse, ::mavsdk::rpc::camera::ZoomRangeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_ZoomRange_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>* CameraService::Stub::AsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncZoomRangeRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::mavsdk::rpc::camera::TrackPointResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_TrackPoint_, context, request, response); +} + +void CameraService::Stub::async::TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackPoint_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackPoint_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>* CameraService::Stub::PrepareAsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::TrackPointResponse, ::mavsdk::rpc::camera::TrackPointRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_TrackPoint_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>* CameraService::Stub::AsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncTrackPointRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::mavsdk::rpc::camera::TrackRectangleResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_TrackRectangle_, context, request, response); +} + +void CameraService::Stub::async::TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackRectangle_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackRectangle_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>* CameraService::Stub::PrepareAsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::TrackRectangleResponse, ::mavsdk::rpc::camera::TrackRectangleRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_TrackRectangle_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>* CameraService::Stub::AsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncTrackRectangleRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::mavsdk::rpc::camera::TrackStopResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_TrackStop_, context, request, response); +} + +void CameraService::Stub::async::TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackStop_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_TrackStop_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>* CameraService::Stub::PrepareAsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::TrackStopResponse, ::mavsdk::rpc::camera::TrackStopRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_TrackStop_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>* CameraService::Stub::AsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncTrackStopRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::mavsdk::rpc::camera::FocusInStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_FocusInStart_, context, request, response); +} + +void CameraService::Stub::async::FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusInStart_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusInStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>* CameraService::Stub::PrepareAsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::FocusInStartResponse, ::mavsdk::rpc::camera::FocusInStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_FocusInStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>* CameraService::Stub::AsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncFocusInStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::mavsdk::rpc::camera::FocusOutStartResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_FocusOutStart_, context, request, response); +} + +void CameraService::Stub::async::FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusOutStart_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusOutStart_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>* CameraService::Stub::PrepareAsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::FocusOutStartResponse, ::mavsdk::rpc::camera::FocusOutStartRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_FocusOutStart_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>* CameraService::Stub::AsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncFocusOutStartRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::mavsdk::rpc::camera::FocusStopResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_FocusStop_, context, request, response); +} + +void CameraService::Stub::async::FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusStop_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusStop_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>* CameraService::Stub::PrepareAsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::FocusStopResponse, ::mavsdk::rpc::camera::FocusStopRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_FocusStop_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>* CameraService::Stub::AsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncFocusStopRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status CameraService::Stub::FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::mavsdk::rpc::camera::FocusRangeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_FocusRange_, context, request, response); +} + +void CameraService::Stub::async::FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusRange_, context, request, response, std::move(f)); +} + +void CameraService::Stub::async::FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_FocusRange_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>* CameraService::Stub::PrepareAsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::camera::FocusRangeResponse, ::mavsdk::rpc::camera::FocusRangeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_FocusRange_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>* CameraService::Stub::AsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncFocusRangeRaw(context, request, cq); + result->StartCall(); + return result; +} + CameraService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( CameraService_method_names[0], @@ -757,6 +1032,116 @@ CameraService::Service::Service() { ::mavsdk::rpc::camera::ResetSettingsResponse* resp) { return service->ResetSettings(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[22], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::ZoomInStartRequest* req, + ::mavsdk::rpc::camera::ZoomInStartResponse* resp) { + return service->ZoomInStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[23], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::ZoomOutStartRequest* req, + ::mavsdk::rpc::camera::ZoomOutStartResponse* resp) { + return service->ZoomOutStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[24], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::ZoomStopRequest* req, + ::mavsdk::rpc::camera::ZoomStopResponse* resp) { + return service->ZoomStop(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[25], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::ZoomRangeRequest* req, + ::mavsdk::rpc::camera::ZoomRangeResponse* resp) { + return service->ZoomRange(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[26], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::TrackPointRequest* req, + ::mavsdk::rpc::camera::TrackPointResponse* resp) { + return service->TrackPoint(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[27], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::TrackRectangleRequest* req, + ::mavsdk::rpc::camera::TrackRectangleResponse* resp) { + return service->TrackRectangle(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[28], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::TrackStopRequest* req, + ::mavsdk::rpc::camera::TrackStopResponse* resp) { + return service->TrackStop(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[29], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::FocusInStartRequest* req, + ::mavsdk::rpc::camera::FocusInStartResponse* resp) { + return service->FocusInStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[30], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::FocusOutStartRequest* req, + ::mavsdk::rpc::camera::FocusOutStartResponse* resp) { + return service->FocusOutStart(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[31], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::FocusStopRequest* req, + ::mavsdk::rpc::camera::FocusStopResponse* resp) { + return service->FocusStop(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + CameraService_method_names[32], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::camera::FocusRangeRequest* req, + ::mavsdk::rpc::camera::FocusRangeResponse* resp) { + return service->FocusRange(ctx, req, resp); + }, this))); } CameraService::Service::~Service() { @@ -916,6 +1301,83 @@ ::grpc::Status CameraService::Service::ResetSettings(::grpc::ServerContext* cont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status CameraService::Service::ZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::ZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::ZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::ZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::TrackPoint(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::TrackRectangle(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::TrackStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::FocusInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::FocusOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::FocusStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status CameraService::Service::FocusRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h index 5c8955af32..49a02a550e 100644 --- a/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.grpc.pb.h @@ -248,7 +248,7 @@ class CameraService final { // // Select current camera . // - // Bind the plugin instance to a specific camera_id + // 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)); @@ -267,6 +267,105 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>> PrepareAsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ResetSettingsResponse>>(PrepareAsyncResetSettingsRaw(context, request, cq)); } + // + // Start zooming in. + virtual ::grpc::Status ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::mavsdk::rpc::camera::ZoomInStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>> AsyncZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>>(AsyncZoomInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>> PrepareAsyncZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>>(PrepareAsyncZoomInStartRaw(context, request, cq)); + } + // + // Start zooming out. + virtual ::grpc::Status ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>> AsyncZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>>(AsyncZoomOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>> PrepareAsyncZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>>(PrepareAsyncZoomOutStartRaw(context, request, cq)); + } + // + // Stop zooming. + virtual ::grpc::Status ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::mavsdk::rpc::camera::ZoomStopResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>> AsyncZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>>(AsyncZoomStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>> PrepareAsyncZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>>(PrepareAsyncZoomStopRaw(context, request, cq)); + } + // + // Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + virtual ::grpc::Status ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::mavsdk::rpc::camera::ZoomRangeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>> AsyncZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>>(AsyncZoomRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>> PrepareAsyncZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>>(PrepareAsyncZoomRangeRaw(context, request, cq)); + } + // + // Track point. + virtual ::grpc::Status TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::mavsdk::rpc::camera::TrackPointResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>> AsyncTrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>>(AsyncTrackPointRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>> PrepareAsyncTrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>>(PrepareAsyncTrackPointRaw(context, request, cq)); + } + // + // Track rectangle. + virtual ::grpc::Status TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::mavsdk::rpc::camera::TrackRectangleResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>> AsyncTrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>>(AsyncTrackRectangleRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>> PrepareAsyncTrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>>(PrepareAsyncTrackRectangleRaw(context, request, cq)); + } + // + // Stop tracking. + virtual ::grpc::Status TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::mavsdk::rpc::camera::TrackStopResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>> AsyncTrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>>(AsyncTrackStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>> PrepareAsyncTrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>>(PrepareAsyncTrackStopRaw(context, request, cq)); + } + // + // Start focusing in. + virtual ::grpc::Status FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::mavsdk::rpc::camera::FocusInStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>> AsyncFocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>>(AsyncFocusInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>> PrepareAsyncFocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>>(PrepareAsyncFocusInStartRaw(context, request, cq)); + } + // + // Start focusing out. + virtual ::grpc::Status FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::mavsdk::rpc::camera::FocusOutStartResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>> AsyncFocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>>(AsyncFocusOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>> PrepareAsyncFocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>>(PrepareAsyncFocusOutStartRaw(context, request, cq)); + } + // + // Stop focus. + virtual ::grpc::Status FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::mavsdk::rpc::camera::FocusStopResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>> AsyncFocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>>(AsyncFocusStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>> PrepareAsyncFocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>>(PrepareAsyncFocusStopRaw(context, request, cq)); + } + // + // Focus with range value of full range (value between 0.0 and 100.0). + virtual ::grpc::Status FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::mavsdk::rpc::camera::FocusRangeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>> AsyncFocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>>(AsyncFocusRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>> PrepareAsyncFocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>>(PrepareAsyncFocusRangeRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -352,7 +451,7 @@ class CameraService final { // // Select current camera . // - // Bind the plugin instance to a specific camera_id + // 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; // @@ -361,6 +460,50 @@ class CameraService final { // This will reset all camera settings to default value virtual void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, std::function) = 0; virtual void ResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Start zooming in. + virtual void ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, std::function) = 0; + virtual void ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Start zooming out. + virtual void ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, std::function) = 0; + virtual void ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Stop zooming. + virtual void ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, std::function) = 0; + virtual void ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + virtual void ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, std::function) = 0; + virtual void ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Track point. + virtual void TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, std::function) = 0; + virtual void TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Track rectangle. + virtual void TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, std::function) = 0; + virtual void TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Stop tracking. + virtual void TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, std::function) = 0; + virtual void TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Start focusing in. + virtual void FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, std::function) = 0; + virtual void FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Start focusing out. + virtual void FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, std::function) = 0; + virtual void FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Stop focus. + virtual void FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, std::function) = 0; + virtual void FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // + // Focus with range value of full range (value between 0.0 and 100.0). + virtual void FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, std::function) = 0; + virtual void FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -417,6 +560,28 @@ class CameraService final { 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; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomInStartResponse>* PrepareAsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>* AsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomOutStartResponse>* PrepareAsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>* AsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomStopResponse>* PrepareAsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>* AsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::ZoomRangeResponse>* PrepareAsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>* AsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackPointResponse>* PrepareAsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>* AsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackRectangleResponse>* PrepareAsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>* AsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::TrackStopResponse>* PrepareAsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>* AsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusInStartResponse>* PrepareAsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>* AsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusOutStartResponse>* PrepareAsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>* AsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusStopResponse>* PrepareAsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>* AsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera::FocusRangeResponse>* PrepareAsyncFocusRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -589,6 +754,83 @@ class CameraService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>> PrepareAsyncResetSettings(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ResetSettingsResponse>>(PrepareAsyncResetSettingsRaw(context, request, cq)); } + ::grpc::Status ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::mavsdk::rpc::camera::ZoomInStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>> AsyncZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>>(AsyncZoomInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>> PrepareAsyncZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>>(PrepareAsyncZoomInStartRaw(context, request, cq)); + } + ::grpc::Status ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>> AsyncZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>>(AsyncZoomOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>> PrepareAsyncZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>>(PrepareAsyncZoomOutStartRaw(context, request, cq)); + } + ::grpc::Status ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::mavsdk::rpc::camera::ZoomStopResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>> AsyncZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>>(AsyncZoomStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>> PrepareAsyncZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>>(PrepareAsyncZoomStopRaw(context, request, cq)); + } + ::grpc::Status ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::mavsdk::rpc::camera::ZoomRangeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>> AsyncZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>>(AsyncZoomRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>> PrepareAsyncZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>>(PrepareAsyncZoomRangeRaw(context, request, cq)); + } + ::grpc::Status TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::mavsdk::rpc::camera::TrackPointResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>> AsyncTrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>>(AsyncTrackPointRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>> PrepareAsyncTrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>>(PrepareAsyncTrackPointRaw(context, request, cq)); + } + ::grpc::Status TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::mavsdk::rpc::camera::TrackRectangleResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>> AsyncTrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>>(AsyncTrackRectangleRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>> PrepareAsyncTrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>>(PrepareAsyncTrackRectangleRaw(context, request, cq)); + } + ::grpc::Status TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::mavsdk::rpc::camera::TrackStopResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>> AsyncTrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>>(AsyncTrackStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>> PrepareAsyncTrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>>(PrepareAsyncTrackStopRaw(context, request, cq)); + } + ::grpc::Status FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::mavsdk::rpc::camera::FocusInStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>> AsyncFocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>>(AsyncFocusInStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>> PrepareAsyncFocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>>(PrepareAsyncFocusInStartRaw(context, request, cq)); + } + ::grpc::Status FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::mavsdk::rpc::camera::FocusOutStartResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>> AsyncFocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>>(AsyncFocusOutStartRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>> PrepareAsyncFocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>>(PrepareAsyncFocusOutStartRaw(context, request, cq)); + } + ::grpc::Status FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::mavsdk::rpc::camera::FocusStopResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>> AsyncFocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>>(AsyncFocusStopRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>> PrepareAsyncFocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>>(PrepareAsyncFocusStopRaw(context, request, cq)); + } + ::grpc::Status FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::mavsdk::rpc::camera::FocusRangeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>> AsyncFocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>>(AsyncFocusRangeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>> PrepareAsyncFocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusRangeResponse>>(PrepareAsyncFocusRangeRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -629,6 +871,28 @@ class CameraService final { 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; + void ZoomInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, std::function) override; + void ZoomOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, std::function) override; + void ZoomStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, std::function) override; + void ZoomRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, std::function) override; + void TrackPoint(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, std::function) override; + void TrackRectangle(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, std::function) override; + void TrackStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, std::function) override; + void FocusInStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, std::function) override; + void FocusOutStart(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, std::function) override; + void FocusStop(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, std::function) override; + void FocusRange(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -691,6 +955,28 @@ class CameraService final { ::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; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomInStartResponse>* PrepareAsyncZoomInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>* AsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomOutStartResponse>* PrepareAsyncZoomOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>* AsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomStopResponse>* PrepareAsyncZoomStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>* AsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::ZoomRangeResponse>* PrepareAsyncZoomRangeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>* AsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackPointResponse>* PrepareAsyncTrackPointRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackPointRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>* AsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackRectangleResponse>* PrepareAsyncTrackRectangleRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>* AsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::TrackStopResponse>* PrepareAsyncTrackStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::TrackStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>* AsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusInStartResponse>* PrepareAsyncFocusInStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>* AsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusOutStartResponse>* PrepareAsyncFocusOutStartRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::camera::FocusStopResponse>* AsyncFocusStopRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::camera::FocusStopRequest& request, ::grpc::CompletionQueue* cq) override; + ::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_; @@ -713,6 +999,17 @@ class CameraService final { 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_; + const ::grpc::internal::RpcMethod rpcmethod_ZoomStop_; + const ::grpc::internal::RpcMethod rpcmethod_ZoomRange_; + const ::grpc::internal::RpcMethod rpcmethod_TrackPoint_; + const ::grpc::internal::RpcMethod rpcmethod_TrackRectangle_; + const ::grpc::internal::RpcMethod rpcmethod_TrackStop_; + const ::grpc::internal::RpcMethod rpcmethod_FocusInStart_; + const ::grpc::internal::RpcMethod rpcmethod_FocusOutStart_; + const ::grpc::internal::RpcMethod rpcmethod_FocusStop_; + const ::grpc::internal::RpcMethod rpcmethod_FocusRange_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -789,13 +1086,46 @@ class CameraService final { // // Select current camera . // - // Bind the plugin instance to a specific camera_id + // Bind the plugin instance to a specific camera_id virtual ::grpc::Status SelectCamera(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::SelectCameraRequest* request, ::mavsdk::rpc::camera::SelectCameraResponse* response); // // Reset all settings in camera. // // This will reset all camera settings to default value virtual ::grpc::Status ResetSettings(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ResetSettingsRequest* request, ::mavsdk::rpc::camera::ResetSettingsResponse* response); + // + // Start zooming in. + virtual ::grpc::Status ZoomInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomInStartRequest* request, ::mavsdk::rpc::camera::ZoomInStartResponse* response); + // + // Start zooming out. + virtual ::grpc::Status ZoomOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomOutStartRequest* request, ::mavsdk::rpc::camera::ZoomOutStartResponse* response); + // + // Stop zooming. + virtual ::grpc::Status ZoomStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomStopRequest* request, ::mavsdk::rpc::camera::ZoomStopResponse* response); + // + // Zoom to value as proportion of full camera range (percentage between 0.0 and 100.0). + virtual ::grpc::Status ZoomRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::ZoomRangeRequest* request, ::mavsdk::rpc::camera::ZoomRangeResponse* response); + // + // Track point. + virtual ::grpc::Status TrackPoint(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackPointRequest* request, ::mavsdk::rpc::camera::TrackPointResponse* response); + // + // Track rectangle. + virtual ::grpc::Status TrackRectangle(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackRectangleRequest* request, ::mavsdk::rpc::camera::TrackRectangleResponse* response); + // + // Stop tracking. + virtual ::grpc::Status TrackStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::TrackStopRequest* request, ::mavsdk::rpc::camera::TrackStopResponse* response); + // + // Start focusing in. + virtual ::grpc::Status FocusInStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusInStartRequest* request, ::mavsdk::rpc::camera::FocusInStartResponse* response); + // + // Start focusing out. + virtual ::grpc::Status FocusOutStart(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusOutStartRequest* request, ::mavsdk::rpc::camera::FocusOutStartResponse* response); + // + // Stop focus. + virtual ::grpc::Status FocusStop(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusStopRequest* request, ::mavsdk::rpc::camera::FocusStopResponse* response); + // + // Focus with range value of full range (value between 0.0 and 100.0). + virtual ::grpc::Status FocusRange(::grpc::ServerContext* context, const ::mavsdk::rpc::camera::FocusRangeRequest* request, ::mavsdk::rpc::camera::FocusRangeResponse* response); }; template class WithAsyncMethod_Prepare : public BaseClass { @@ -1237,7 +1567,227 @@ class CameraService final { ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_Prepare > > > > > > > > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_ZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ZoomInStart() { + ::grpc::Service::MarkMethodAsync(22); + } + ~WithAsyncMethod_ZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_ZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ZoomOutStart() { + ::grpc::Service::MarkMethodAsync(23); + } + ~WithAsyncMethod_ZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_ZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ZoomStop() { + ::grpc::Service::MarkMethodAsync(24); + } + ~WithAsyncMethod_ZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_ZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_ZoomRange() { + ::grpc::Service::MarkMethodAsync(25); + } + ~WithAsyncMethod_ZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_TrackPoint : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_TrackPoint() { + ::grpc::Service::MarkMethodAsync(26); + } + ~WithAsyncMethod_TrackPoint() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_TrackRectangle : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_TrackRectangle() { + ::grpc::Service::MarkMethodAsync(27); + } + ~WithAsyncMethod_TrackRectangle() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_TrackStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_TrackStop() { + ::grpc::Service::MarkMethodAsync(28); + } + ~WithAsyncMethod_TrackStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_FocusInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_FocusInStart() { + ::grpc::Service::MarkMethodAsync(29); + } + ~WithAsyncMethod_FocusInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_FocusOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_FocusOutStart() { + ::grpc::Service::MarkMethodAsync(30); + } + ~WithAsyncMethod_FocusOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_FocusStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_FocusStop() { + ::grpc::Service::MarkMethodAsync(31); + } + ~WithAsyncMethod_FocusStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithAsyncMethod_FocusRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_FocusRange() { + ::grpc::Service::MarkMethodAsync(32); + } + ~WithAsyncMethod_FocusRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { + abort(); + 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: @@ -1797,89 +2347,386 @@ class CameraService final { virtual ::grpc::ServerUnaryReactor* ResetSettings( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_Prepare > > > > > > > > > > > > > > > > > > > > > CallbackService; - typedef CallbackService ExperimentalCallbackService; template - class WithGenericMethod_Prepare : public BaseClass { + class WithCallbackMethod_ZoomInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_Prepare() { - ::grpc::Service::MarkMethodGeneric(0); + WithCallbackMethod_ZoomInStart() { + ::grpc::Service::MarkMethodCallback(22, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_Prepare() override { + ~WithCallbackMethod_ZoomInStart() 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 { + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } + virtual ::grpc::ServerUnaryReactor* ZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) { return nullptr; } }; template - class WithGenericMethod_TakePhoto : public BaseClass { + class WithCallbackMethod_ZoomOutStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_TakePhoto() { - ::grpc::Service::MarkMethodGeneric(1); + WithCallbackMethod_ZoomOutStart() { + ::grpc::Service::MarkMethodCallback(23, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_TakePhoto() override { + ~WithCallbackMethod_ZoomOutStart() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status TakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TakePhotoRequest* /*request*/, ::mavsdk::rpc::camera::TakePhotoResponse* /*response*/) override { + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } + virtual ::grpc::ServerUnaryReactor* ZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) { return nullptr; } }; template - class WithGenericMethod_StartPhotoInterval : public BaseClass { + class WithCallbackMethod_ZoomStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodGeneric(2); + WithCallbackMethod_ZoomStop() { + ::grpc::Service::MarkMethodCallback(24, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_StartPhotoInterval() override { + ~WithCallbackMethod_ZoomStop() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StartPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* /*response*/) override { + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } + virtual ::grpc::ServerUnaryReactor* ZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) { return nullptr; } }; template - class WithGenericMethod_StopPhotoInterval : public BaseClass { + class WithCallbackMethod_ZoomRange : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodGeneric(3); + WithCallbackMethod_ZoomRange() { + ::grpc::Service::MarkMethodCallback(25, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_StopPhotoInterval() override { + ~WithCallbackMethod_ZoomRange() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StopPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StopPhotoIntervalResponse* /*response*/) override { + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } + virtual ::grpc::ServerUnaryReactor* ZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) { return nullptr; } }; template - class WithGenericMethod_StartVideo : public BaseClass { + class WithCallbackMethod_TrackPoint : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_StartVideo() { - ::grpc::Service::MarkMethodGeneric(4); + WithCallbackMethod_TrackPoint() { + ::grpc::Service::MarkMethodCallback(26, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>*>(handler) + ->SetMessageAllocator(allocator); } - ~WithGenericMethod_StartVideo() override { + ~WithCallbackMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoResponse* /*response*/) override { + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* TrackPoint( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_TrackRectangle : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_TrackRectangle() { + ::grpc::Service::MarkMethodCallback(27, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_TrackRectangle() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* TrackRectangle( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_TrackStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_TrackStop() { + ::grpc::Service::MarkMethodCallback(28, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_TrackStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* TrackStop( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_FocusInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_FocusInStart() { + ::grpc::Service::MarkMethodCallback(29, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_FocusInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* FocusInStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_FocusOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_FocusOutStart() { + ::grpc::Service::MarkMethodCallback(30, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_FocusOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* FocusOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_FocusStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_FocusStop() { + ::grpc::Service::MarkMethodCallback(31, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_FocusStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* FocusStop( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_FocusRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_FocusRange() { + ::grpc::Service::MarkMethodCallback(32, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_FocusRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + 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 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); + } + ~WithGenericMethod_TakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TakePhotoRequest* /*request*/, ::mavsdk::rpc::camera::TakePhotoResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_StartPhotoInterval : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_StartPhotoInterval() { + ::grpc::Service::MarkMethodGeneric(2); + } + ~WithGenericMethod_StartPhotoInterval() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_StopPhotoInterval : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_StopPhotoInterval() { + ::grpc::Service::MarkMethodGeneric(3); + } + ~WithGenericMethod_StopPhotoInterval() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StopPhotoIntervalResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_StartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_StartVideo() { + ::grpc::Service::MarkMethodGeneric(4); + } + ~WithGenericMethod_StartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -2174,222 +3021,409 @@ class CameraService final { } }; template - class WithRawMethod_Prepare : public BaseClass { + class WithGenericMethod_ZoomInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_Prepare() { - ::grpc::Service::MarkMethodRaw(0); + WithGenericMethod_ZoomInStart() { + ::grpc::Service::MarkMethodGeneric(22); } - ~WithRawMethod_Prepare() override { + ~WithGenericMethod_ZoomInStart() 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 { + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*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 { + class WithGenericMethod_ZoomOutStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_TakePhoto() { - ::grpc::Service::MarkMethodRaw(1); + WithGenericMethod_ZoomOutStart() { + ::grpc::Service::MarkMethodGeneric(23); } - ~WithRawMethod_TakePhoto() override { + ~WithGenericMethod_ZoomOutStart() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status TakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TakePhotoRequest* /*request*/, ::mavsdk::rpc::camera::TakePhotoResponse* /*response*/) override { + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StartPhotoInterval : public BaseClass { + class WithGenericMethod_ZoomStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StartPhotoInterval() { - ::grpc::Service::MarkMethodRaw(2); + WithGenericMethod_ZoomStop() { + ::grpc::Service::MarkMethodGeneric(24); } - ~WithRawMethod_StartPhotoInterval() override { + ~WithGenericMethod_ZoomStop() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StartPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* /*response*/) override { + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StopPhotoInterval : public BaseClass { + class WithGenericMethod_ZoomRange : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StopPhotoInterval() { - ::grpc::Service::MarkMethodRaw(3); + WithGenericMethod_ZoomRange() { + ::grpc::Service::MarkMethodGeneric(25); } - ~WithRawMethod_StopPhotoInterval() override { + ~WithGenericMethod_ZoomRange() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StopPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StopPhotoIntervalResponse* /*response*/) override { + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StartVideo : public BaseClass { + class WithGenericMethod_TrackPoint : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StartVideo() { - ::grpc::Service::MarkMethodRaw(4); + WithGenericMethod_TrackPoint() { + ::grpc::Service::MarkMethodGeneric(26); } - ~WithRawMethod_StartVideo() override { + ~WithGenericMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoResponse* /*response*/) override { + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StopVideo : public BaseClass { + class WithGenericMethod_TrackRectangle : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StopVideo() { - ::grpc::Service::MarkMethodRaw(5); + WithGenericMethod_TrackRectangle() { + ::grpc::Service::MarkMethodGeneric(27); } - ~WithRawMethod_StopVideo() override { + ~WithGenericMethod_TrackRectangle() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopVideoRequest* /*request*/, ::mavsdk::rpc::camera::StopVideoResponse* /*response*/) override { + ::grpc::Status TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StartVideoStreaming : public BaseClass { + class WithGenericMethod_TrackStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StartVideoStreaming() { - ::grpc::Service::MarkMethodRaw(6); + WithGenericMethod_TrackStop() { + ::grpc::Service::MarkMethodGeneric(28); } - ~WithRawMethod_StartVideoStreaming() override { + ~WithGenericMethod_TrackStop() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoStreamingResponse* /*response*/) override { + ::grpc::Status TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_StopVideoStreaming : public BaseClass { + class WithGenericMethod_FocusInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_StopVideoStreaming() { - ::grpc::Service::MarkMethodRaw(7); + WithGenericMethod_FocusInStart() { + ::grpc::Service::MarkMethodGeneric(29); } - ~WithRawMethod_StopVideoStreaming() override { + ~WithGenericMethod_FocusInStart() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status StopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera::StopVideoStreamingResponse* /*response*/) override { + ::grpc::Status FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_SetMode : public BaseClass { + class WithGenericMethod_FocusOutStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SetMode() { - ::grpc::Service::MarkMethodRaw(8); + WithGenericMethod_FocusOutStart() { + ::grpc::Service::MarkMethodGeneric(30); } - ~WithRawMethod_SetMode() override { + ~WithGenericMethod_FocusOutStart() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SetModeRequest* /*request*/, ::mavsdk::rpc::camera::SetModeResponse* /*response*/) override { + ::grpc::Status FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_ListPhotos : public BaseClass { + class WithGenericMethod_FocusStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_ListPhotos() { - ::grpc::Service::MarkMethodRaw(9); + WithGenericMethod_FocusStop() { + ::grpc::Service::MarkMethodGeneric(31); } - ~WithRawMethod_ListPhotos() override { + ~WithGenericMethod_FocusStop() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status ListPhotos(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ListPhotosRequest* /*request*/, ::mavsdk::rpc::camera::ListPhotosResponse* /*response*/) override { + ::grpc::Status FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) override { abort(); 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); - } }; template - class WithRawMethod_SubscribeMode : public BaseClass { + class WithGenericMethod_FocusRange : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SubscribeMode() { - ::grpc::Service::MarkMethodRaw(10); + WithGenericMethod_FocusRange() { + ::grpc::Service::MarkMethodGeneric(32); } - ~WithRawMethod_SubscribeMode() override { + ~WithGenericMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous 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 FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSubscribeMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + }; + 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); + } + ~WithRawMethod_TakePhoto() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TakePhoto(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TakePhotoRequest* /*request*/, ::mavsdk::rpc::camera::TakePhotoResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StartPhotoInterval : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StartPhotoInterval() { + ::grpc::Service::MarkMethodRaw(2); + } + ~WithRawMethod_StartPhotoInterval() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StartPhotoIntervalResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StopPhotoInterval : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StopPhotoInterval() { + ::grpc::Service::MarkMethodRaw(3); + } + ~WithRawMethod_StopPhotoInterval() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopPhotoInterval(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopPhotoIntervalRequest* /*request*/, ::mavsdk::rpc::camera::StopPhotoIntervalResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StartVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StartVideo() { + ::grpc::Service::MarkMethodRaw(4); + } + ~WithRawMethod_StartVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StopVideo : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StopVideo() { + ::grpc::Service::MarkMethodRaw(5); + } + ~WithRawMethod_StopVideo() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopVideo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopVideoRequest* /*request*/, ::mavsdk::rpc::camera::StopVideoResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StartVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StartVideoStreaming() { + ::grpc::Service::MarkMethodRaw(6); + } + ~WithRawMethod_StartVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StartVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StartVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera::StartVideoStreamingResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_StopVideoStreaming : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_StopVideoStreaming() { + ::grpc::Service::MarkMethodRaw(7); + } + ~WithRawMethod_StopVideoStreaming() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status StopVideoStreaming(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::StopVideoStreamingRequest* /*request*/, ::mavsdk::rpc::camera::StopVideoStreamingResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_SetMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetMode() { + ::grpc::Service::MarkMethodRaw(8); + } + ~WithRawMethod_SetMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetMode(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SetModeRequest* /*request*/, ::mavsdk::rpc::camera::SetModeResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_ListPhotos : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ListPhotos() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_ListPhotos() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ListPhotos(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ListPhotosRequest* /*request*/, ::mavsdk::rpc::camera::ListPhotosResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_SubscribeMode : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeMode() { + ::grpc::Service::MarkMethodRaw(10); + } + ~WithRawMethod_SubscribeMode() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::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, ""); + } + void RequestSubscribeMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); } }; @@ -2494,123 +3528,343 @@ class CameraService final { } }; template - class WithRawMethod_SubscribePossibleSettingOptions : public BaseClass { + class WithRawMethod_SubscribePossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribePossibleSettingOptions() { + ::grpc::Service::MarkMethodRaw(16); + } + ~WithRawMethod_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, ""); + } + 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); + } + }; + template + class WithRawMethod_SetSetting : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetSetting() { + ::grpc::Service::MarkMethodRaw(17); + } + ~WithRawMethod_SetSetting() 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 { + abort(); + 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); + } + }; + template + class WithRawMethod_GetSetting : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetSetting() { + ::grpc::Service::MarkMethodRaw(18); + } + ~WithRawMethod_GetSetting() 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 { + abort(); + 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); + } + }; + template + class WithRawMethod_FormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_FormatStorage() { + ::grpc::Service::MarkMethodRaw(19); + } + ~WithRawMethod_FormatStorage() 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 { + abort(); + 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); + } + }; + template + class WithRawMethod_ResetSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ResetSettings() { + ::grpc::Service::MarkMethodRaw(21); + } + ~WithRawMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestResetSettings(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_ZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ZoomInStart() { + ::grpc::Service::MarkMethodRaw(22); + } + ~WithRawMethod_ZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_ZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ZoomOutStart() { + ::grpc::Service::MarkMethodRaw(23); + } + ~WithRawMethod_ZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_ZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ZoomStop() { + ::grpc::Service::MarkMethodRaw(24); + } + ~WithRawMethod_ZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_ZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_ZoomRange() { + ::grpc::Service::MarkMethodRaw(25); + } + ~WithRawMethod_ZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_TrackPoint : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_TrackPoint() { + ::grpc::Service::MarkMethodRaw(26); + } + ~WithRawMethod_TrackPoint() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { + abort(); + 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); + } + }; + template + class WithRawMethod_TrackRectangle : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodRaw(16); + WithRawMethod_TrackRectangle() { + ::grpc::Service::MarkMethodRaw(27); } - ~WithRawMethod_SubscribePossibleSettingOptions() override { + ~WithRawMethod_TrackRectangle() 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 TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) override { abort(); 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); + 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); } }; template - class WithRawMethod_SetSetting : public BaseClass { + class WithRawMethod_TrackStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SetSetting() { - ::grpc::Service::MarkMethodRaw(17); + WithRawMethod_TrackStop() { + ::grpc::Service::MarkMethodRaw(28); } - ~WithRawMethod_SetSetting() override { + ~WithRawMethod_TrackStop() 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 TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { abort(); 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); + 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); } }; template - class WithRawMethod_GetSetting : public BaseClass { + class WithRawMethod_FocusInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_GetSetting() { - ::grpc::Service::MarkMethodRaw(18); + WithRawMethod_FocusInStart() { + ::grpc::Service::MarkMethodRaw(29); } - ~WithRawMethod_GetSetting() override { + ~WithRawMethod_FocusInStart() 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 FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { abort(); 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); + 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); } }; template - class WithRawMethod_FormatStorage : public BaseClass { + class WithRawMethod_FocusOutStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_FormatStorage() { - ::grpc::Service::MarkMethodRaw(19); + WithRawMethod_FocusOutStart() { + ::grpc::Service::MarkMethodRaw(30); } - ~WithRawMethod_FormatStorage() override { + ~WithRawMethod_FocusOutStart() 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 FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { abort(); 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); + 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); } }; template - class WithRawMethod_SelectCamera : public BaseClass { + class WithRawMethod_FocusStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SelectCamera() { - ::grpc::Service::MarkMethodRaw(20); + WithRawMethod_FocusStop() { + ::grpc::Service::MarkMethodRaw(31); } - ~WithRawMethod_SelectCamera() override { + ~WithRawMethod_FocusStop() 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 FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*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); + 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); } }; template - class WithRawMethod_ResetSettings : public BaseClass { + class WithRawMethod_FocusRange : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_ResetSettings() { - ::grpc::Service::MarkMethodRaw(21); + WithRawMethod_FocusRange() { + ::grpc::Service::MarkMethodRaw(32); } - ~WithRawMethod_ResetSettings() override { + ~WithRawMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + ::grpc::Status FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestResetSettings(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(21, context, request, response, new_call_cq, notification_cq, tag); + 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); } }; template @@ -2944,157 +4198,399 @@ class CameraService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template - class WithRawCallbackMethod_SubscribeCurrentSettings : public BaseClass { + class WithRawCallbackMethod_SubscribeCurrentSettings : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeCurrentSettings() { + ::grpc::Service::MarkMethodRawCallback(15, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCurrentSettings(context, request); })); + } + ~WithRawCallbackMethod_SubscribeCurrentSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CurrentSettingsResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCurrentSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_SubscribePossibleSettingOptions : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribePossibleSettingOptions() { + ::grpc::Service::MarkMethodRawCallback(16, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::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_SetSetting : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetSetting() { + ::grpc::Service::MarkMethodRawCallback(17, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetSetting(context, request, response); })); + } + ~WithRawCallbackMethod_SetSetting() 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 { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetSetting( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_GetSetting : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetSetting() { + ::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->GetSetting(context, request, response); })); + } + ~WithRawCallbackMethod_GetSetting() 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 { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetSetting( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_FormatStorage : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_FormatStorage() { + ::grpc::Service::MarkMethodRawCallback(19, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FormatStorage(context, request, response); })); + } + ~WithRawCallbackMethod_FormatStorage() 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 { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* FormatStorage( + ::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, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ResetSettings(context, request, response); })); + } + ~WithRawCallbackMethod_ResetSettings() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ResetSettings( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_ZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ZoomInStart() { + ::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->ZoomInStart(context, request, response); })); + } + ~WithRawCallbackMethod_ZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ZoomInStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_ZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ZoomOutStart() { + ::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->ZoomOutStart(context, request, response); })); + } + ~WithRawCallbackMethod_ZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ZoomOutStart( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_ZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ZoomStop() { + ::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->ZoomStop(context, request, response); })); + } + ~WithRawCallbackMethod_ZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ZoomStop( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_ZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_ZoomRange() { + ::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->ZoomRange(context, request, response); })); + } + ~WithRawCallbackMethod_ZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* ZoomRange( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_TrackPoint : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SubscribeCurrentSettings() { - ::grpc::Service::MarkMethodRawCallback(15, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + WithRawCallbackMethod_TrackPoint() { + ::grpc::Service::MarkMethodRawCallback(26, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCurrentSettings(context, request); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackPoint(context, request, response); })); } - ~WithRawCallbackMethod_SubscribeCurrentSettings() override { + ~WithRawCallbackMethod_TrackPoint() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeCurrentSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::SubscribeCurrentSettingsRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::camera::CurrentSettingsResponse>* /*writer*/) override { + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCurrentSettings( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + virtual ::grpc::ServerUnaryReactor* TrackPoint( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SubscribePossibleSettingOptions : public BaseClass { + class WithRawCallbackMethod_TrackRectangle : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SubscribePossibleSettingOptions() { - ::grpc::Service::MarkMethodRawCallback(16, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + WithRawCallbackMethod_TrackRectangle() { + ::grpc::Service::MarkMethodRawCallback(27, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribePossibleSettingOptions(context, request); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackRectangle(context, request, response); })); } - ~WithRawCallbackMethod_SubscribePossibleSettingOptions() override { + ~WithRawCallbackMethod_TrackRectangle() 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 TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*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* TrackRectangle( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SetSetting : public BaseClass { + class WithRawCallbackMethod_TrackStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SetSetting() { - ::grpc::Service::MarkMethodRawCallback(17, + WithRawCallbackMethod_TrackStop() { + ::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->SetSetting(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->TrackStop(context, request, response); })); } - ~WithRawCallbackMethod_SetSetting() override { + ~WithRawCallbackMethod_TrackStop() 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 TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* SetSetting( + virtual ::grpc::ServerUnaryReactor* TrackStop( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_GetSetting : public BaseClass { + class WithRawCallbackMethod_FocusInStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_GetSetting() { - ::grpc::Service::MarkMethodRawCallback(18, + WithRawCallbackMethod_FocusInStart() { + ::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->GetSetting(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusInStart(context, request, response); })); } - ~WithRawCallbackMethod_GetSetting() override { + ~WithRawCallbackMethod_FocusInStart() 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 FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* GetSetting( + virtual ::grpc::ServerUnaryReactor* FocusInStart( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_FormatStorage : public BaseClass { + class WithRawCallbackMethod_FocusOutStart : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_FormatStorage() { - ::grpc::Service::MarkMethodRawCallback(19, + WithRawCallbackMethod_FocusOutStart() { + ::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->FormatStorage(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusOutStart(context, request, response); })); } - ~WithRawCallbackMethod_FormatStorage() override { + ~WithRawCallbackMethod_FocusOutStart() 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 FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* FormatStorage( + virtual ::grpc::ServerUnaryReactor* FocusOutStart( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SelectCamera : public BaseClass { + class WithRawCallbackMethod_FocusStop : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SelectCamera() { - ::grpc::Service::MarkMethodRawCallback(20, + WithRawCallbackMethod_FocusStop() { + ::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->SelectCamera(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusStop(context, request, response); })); } - ~WithRawCallbackMethod_SelectCamera() override { + ~WithRawCallbackMethod_FocusStop() 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 FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* SelectCamera( + virtual ::grpc::ServerUnaryReactor* FocusStop( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_ResetSettings : public BaseClass { + class WithRawCallbackMethod_FocusRange : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_ResetSettings() { - ::grpc::Service::MarkMethodRawCallback(21, + WithRawCallbackMethod_FocusRange() { + ::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->ResetSettings(context, request, response); })); + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->FocusRange(context, request, response); })); } - ~WithRawCallbackMethod_ResetSettings() override { + ~WithRawCallbackMethod_FocusRange() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status ResetSettings(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ResetSettingsRequest* /*request*/, ::mavsdk::rpc::camera::ResetSettingsResponse* /*response*/) override { + ::grpc::Status FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerUnaryReactor* ResetSettings( + virtual ::grpc::ServerUnaryReactor* FocusRange( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template @@ -3502,7 +4998,304 @@ class CameraService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedResetSettings(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ResetSettingsRequest,::mavsdk::rpc::camera::ResetSettingsResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_ZoomInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ZoomInStart() { + ::grpc::Service::MarkMethodStreamed(22, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::ZoomInStartRequest, ::mavsdk::rpc::camera::ZoomInStartResponse>* streamer) { + return this->StreamedZoomInStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ZoomInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ZoomInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomInStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedZoomInStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ZoomInStartRequest,::mavsdk::rpc::camera::ZoomInStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_ZoomOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ZoomOutStart() { + ::grpc::Service::MarkMethodStreamed(23, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::ZoomOutStartRequest, ::mavsdk::rpc::camera::ZoomOutStartResponse>* streamer) { + return this->StreamedZoomOutStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ZoomOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ZoomOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomOutStartRequest* /*request*/, ::mavsdk::rpc::camera::ZoomOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedZoomOutStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ZoomOutStartRequest,::mavsdk::rpc::camera::ZoomOutStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_ZoomStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ZoomStop() { + ::grpc::Service::MarkMethodStreamed(24, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::ZoomStopRequest, ::mavsdk::rpc::camera::ZoomStopResponse>* streamer) { + return this->StreamedZoomStop(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ZoomStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ZoomStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomStopRequest* /*request*/, ::mavsdk::rpc::camera::ZoomStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedZoomStop(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ZoomStopRequest,::mavsdk::rpc::camera::ZoomStopResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_ZoomRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_ZoomRange() { + ::grpc::Service::MarkMethodStreamed(25, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::ZoomRangeRequest, ::mavsdk::rpc::camera::ZoomRangeResponse>* streamer) { + return this->StreamedZoomRange(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_ZoomRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status ZoomRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::ZoomRangeRequest* /*request*/, ::mavsdk::rpc::camera::ZoomRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedZoomRange(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::ZoomRangeRequest,::mavsdk::rpc::camera::ZoomRangeResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_TrackPoint : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_TrackPoint() { + ::grpc::Service::MarkMethodStreamed(26, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::TrackPointRequest, ::mavsdk::rpc::camera::TrackPointResponse>* streamer) { + return this->StreamedTrackPoint(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_TrackPoint() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status TrackPoint(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackPointRequest* /*request*/, ::mavsdk::rpc::camera::TrackPointResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedTrackPoint(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::TrackPointRequest,::mavsdk::rpc::camera::TrackPointResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_TrackRectangle : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_TrackRectangle() { + ::grpc::Service::MarkMethodStreamed(27, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::TrackRectangleRequest, ::mavsdk::rpc::camera::TrackRectangleResponse>* streamer) { + return this->StreamedTrackRectangle(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_TrackRectangle() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status TrackRectangle(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackRectangleRequest* /*request*/, ::mavsdk::rpc::camera::TrackRectangleResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedTrackRectangle(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::TrackRectangleRequest,::mavsdk::rpc::camera::TrackRectangleResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_TrackStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_TrackStop() { + ::grpc::Service::MarkMethodStreamed(28, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::TrackStopRequest, ::mavsdk::rpc::camera::TrackStopResponse>* streamer) { + return this->StreamedTrackStop(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_TrackStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status TrackStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::TrackStopRequest* /*request*/, ::mavsdk::rpc::camera::TrackStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedTrackStop(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::TrackStopRequest,::mavsdk::rpc::camera::TrackStopResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_FocusInStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_FocusInStart() { + ::grpc::Service::MarkMethodStreamed(29, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::FocusInStartRequest, ::mavsdk::rpc::camera::FocusInStartResponse>* streamer) { + return this->StreamedFocusInStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_FocusInStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status FocusInStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusInStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusInStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedFocusInStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::FocusInStartRequest,::mavsdk::rpc::camera::FocusInStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_FocusOutStart : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_FocusOutStart() { + ::grpc::Service::MarkMethodStreamed(30, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::FocusOutStartRequest, ::mavsdk::rpc::camera::FocusOutStartResponse>* streamer) { + return this->StreamedFocusOutStart(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_FocusOutStart() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status FocusOutStart(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusOutStartRequest* /*request*/, ::mavsdk::rpc::camera::FocusOutStartResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedFocusOutStart(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::FocusOutStartRequest,::mavsdk::rpc::camera::FocusOutStartResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_FocusStop : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_FocusStop() { + ::grpc::Service::MarkMethodStreamed(31, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::FocusStopRequest, ::mavsdk::rpc::camera::FocusStopResponse>* streamer) { + return this->StreamedFocusStop(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_FocusStop() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status FocusStop(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusStopRequest* /*request*/, ::mavsdk::rpc::camera::FocusStopResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedFocusStop(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::camera::FocusStopRequest,::mavsdk::rpc::camera::FocusStopResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_FocusRange : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_FocusRange() { + ::grpc::Service::MarkMethodStreamed(32, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::camera::FocusRangeRequest, ::mavsdk::rpc::camera::FocusRangeResponse>* streamer) { + return this->StreamedFocusRange(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_FocusRange() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status FocusRange(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::camera::FocusRangeRequest* /*request*/, ::mavsdk::rpc::camera::FocusRangeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // 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; template class WithSplitStreamingMethod_SubscribeMode : public BaseClass { private: @@ -3693,7 +5486,7 @@ class CameraService final { virtual ::grpc::Status StreamedSubscribePossibleSettingOptions(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::camera::SubscribePossibleSettingOptionsRequest,::mavsdk::rpc::camera::PossibleSettingOptionsResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeMode > > > > > > SplitStreamedService; - typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_Prepare > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace camera diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 6a42fa9005..415cd73036 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -23,6 +23,61 @@ namespace _fl = ::google::protobuf::internal::field_layout; namespace mavsdk { namespace rpc { namespace camera { + template +PROTOBUF_CONSTEXPR ZoomStopRequest::ZoomStopRequest(::_pbi::ConstantInitialized) {} +struct ZoomStopRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomStopRequestDefaultTypeInternal() {} + union { + ZoomStopRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomStopRequestDefaultTypeInternal _ZoomStopRequest_default_instance_; + +inline constexpr ZoomRangeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : range_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ZoomRangeRequest::ZoomRangeRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomRangeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomRangeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomRangeRequestDefaultTypeInternal() {} + union { + ZoomRangeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomRangeRequestDefaultTypeInternal _ZoomRangeRequest_default_instance_; + template +PROTOBUF_CONSTEXPR ZoomOutStartRequest::ZoomOutStartRequest(::_pbi::ConstantInitialized) {} +struct ZoomOutStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomOutStartRequestDefaultTypeInternal() {} + union { + ZoomOutStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomOutStartRequestDefaultTypeInternal _ZoomOutStartRequest_default_instance_; + template +PROTOBUF_CONSTEXPR ZoomInStartRequest::ZoomInStartRequest(::_pbi::ConstantInitialized) {} +struct ZoomInStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomInStartRequestDefaultTypeInternal() {} + union { + ZoomInStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomInStartRequestDefaultTypeInternal _ZoomInStartRequest_default_instance_; inline constexpr VideoStreamSettings::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -51,6 +106,61 @@ struct VideoStreamSettingsDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamSettingsDefaultTypeInternal _VideoStreamSettings_default_instance_; template +PROTOBUF_CONSTEXPR TrackStopRequest::TrackStopRequest(::_pbi::ConstantInitialized) {} +struct TrackStopRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackStopRequestDefaultTypeInternal() {} + union { + TrackStopRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackStopRequestDefaultTypeInternal _TrackStopRequest_default_instance_; + +inline constexpr TrackRectangleRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : top_left_x_{0}, + top_left_y_{0}, + bottom_right_x_{0}, + bottom_right_y_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR TrackRectangleRequest::TrackRectangleRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct TrackRectangleRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackRectangleRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackRectangleRequestDefaultTypeInternal() {} + union { + TrackRectangleRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackRectangleRequestDefaultTypeInternal _TrackRectangleRequest_default_instance_; + +inline constexpr TrackPointRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : point_x_{0}, + point_y_{0}, + radius_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR TrackPointRequest::TrackPointRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct TrackPointRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackPointRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackPointRequestDefaultTypeInternal() {} + union { + TrackPointRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackPointRequestDefaultTypeInternal _TrackPointRequest_default_instance_; + template PROTOBUF_CONSTEXPR TakePhotoRequest::TakePhotoRequest(::_pbi::ConstantInitialized) {} struct TakePhotoRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR TakePhotoRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} @@ -485,6 +595,61 @@ struct FormatStorageRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FormatStorageRequestDefaultTypeInternal _FormatStorageRequest_default_instance_; + template +PROTOBUF_CONSTEXPR FocusStopRequest::FocusStopRequest(::_pbi::ConstantInitialized) {} +struct FocusStopRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusStopRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusStopRequestDefaultTypeInternal() {} + union { + FocusStopRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusStopRequestDefaultTypeInternal _FocusStopRequest_default_instance_; + +inline constexpr FocusRangeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : range_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR FocusRangeRequest::FocusRangeRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct FocusRangeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusRangeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusRangeRequestDefaultTypeInternal() {} + union { + FocusRangeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusRangeRequestDefaultTypeInternal _FocusRangeRequest_default_instance_; + template +PROTOBUF_CONSTEXPR FocusOutStartRequest::FocusOutStartRequest(::_pbi::ConstantInitialized) {} +struct FocusOutStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusOutStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusOutStartRequestDefaultTypeInternal() {} + union { + FocusOutStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusOutStartRequestDefaultTypeInternal _FocusOutStartRequest_default_instance_; + template +PROTOBUF_CONSTEXPR FocusInStartRequest::FocusInStartRequest(::_pbi::ConstantInitialized) {} +struct FocusInStartRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusInStartRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusInStartRequestDefaultTypeInternal() {} + union { + FocusInStartRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusInStartRequestDefaultTypeInternal _FocusInStartRequest_default_instance_; inline constexpr EulerAngle::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -529,6 +694,82 @@ struct CameraResultDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraResultDefaultTypeInternal _CameraResult_default_instance_; +inline constexpr ZoomStopResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR ZoomStopResponse::ZoomStopResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomStopResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomStopResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomStopResponseDefaultTypeInternal() {} + union { + ZoomStopResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomStopResponseDefaultTypeInternal _ZoomStopResponse_default_instance_; + +inline constexpr ZoomRangeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR ZoomRangeResponse::ZoomRangeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomRangeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomRangeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomRangeResponseDefaultTypeInternal() {} + union { + ZoomRangeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomRangeResponseDefaultTypeInternal _ZoomRangeResponse_default_instance_; + +inline constexpr ZoomOutStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR ZoomOutStartResponse::ZoomOutStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomOutStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomOutStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomOutStartResponseDefaultTypeInternal() {} + union { + ZoomOutStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomOutStartResponseDefaultTypeInternal _ZoomOutStartResponse_default_instance_; + +inline constexpr ZoomInStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR ZoomInStartResponse::ZoomInStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct ZoomInStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ZoomInStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ZoomInStartResponseDefaultTypeInternal() {} + union { + ZoomInStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ZoomInStartResponseDefaultTypeInternal _ZoomInStartResponse_default_instance_; + inline constexpr VideoStreamInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -550,6 +791,63 @@ struct VideoStreamInfoDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 VideoStreamInfoDefaultTypeInternal _VideoStreamInfo_default_instance_; +inline constexpr TrackStopResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR TrackStopResponse::TrackStopResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct TrackStopResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackStopResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackStopResponseDefaultTypeInternal() {} + union { + TrackStopResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackStopResponseDefaultTypeInternal _TrackStopResponse_default_instance_; + +inline constexpr TrackRectangleResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR TrackRectangleResponse::TrackRectangleResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct TrackRectangleResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackRectangleResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackRectangleResponseDefaultTypeInternal() {} + union { + TrackRectangleResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackRectangleResponseDefaultTypeInternal _TrackRectangleResponse_default_instance_; + +inline constexpr TrackPointResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR TrackPointResponse::TrackPointResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct TrackPointResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR TrackPointResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~TrackPointResponseDefaultTypeInternal() {} + union { + TrackPointResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TrackPointResponseDefaultTypeInternal _TrackPointResponse_default_instance_; + inline constexpr TakePhotoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -887,6 +1185,82 @@ struct FormatStorageResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FormatStorageResponseDefaultTypeInternal _FormatStorageResponse_default_instance_; +inline constexpr FocusStopResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR FocusStopResponse::FocusStopResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct FocusStopResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusStopResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusStopResponseDefaultTypeInternal() {} + union { + FocusStopResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusStopResponseDefaultTypeInternal _FocusStopResponse_default_instance_; + +inline constexpr FocusRangeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR FocusRangeResponse::FocusRangeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct FocusRangeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusRangeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusRangeResponseDefaultTypeInternal() {} + union { + FocusRangeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusRangeResponseDefaultTypeInternal _FocusRangeResponse_default_instance_; + +inline constexpr FocusOutStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR FocusOutStartResponse::FocusOutStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct FocusOutStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusOutStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusOutStartResponseDefaultTypeInternal() {} + union { + FocusOutStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusOutStartResponseDefaultTypeInternal _FocusOutStartResponse_default_instance_; + +inline constexpr FocusInStartResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + camera_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR FocusInStartResponse::FocusInStartResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct FocusInStartResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR FocusInStartResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~FocusInStartResponseDefaultTypeInternal() {} + union { + FocusInStartResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 FocusInStartResponseDefaultTypeInternal _FocusInStartResponse_default_instance_; + inline constexpr CaptureInfo::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1070,7 +1444,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace camera } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[56]; +static ::_pb::Metadata file_level_metadata_camera_2fcamera_2eproto[78]; 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; @@ -1485,69 +1859,276 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ResetSettingsResponse, _impl_.camera_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraResult, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartRequest, _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::CameraResult, _impl_.result_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraResult, _impl_.result_str_), - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartResponse, _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::Position, _impl_.latitude_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.longitude_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.absolute_altitude_m_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.relative_altitude_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomInStartResponse, _impl_.camera_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomOutStartRequest, _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::Quaternion, _impl_.w_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.x_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.y_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.z_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomOutStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomOutStartResponse, _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::ZoomOutStartResponse, _impl_.camera_result_), + 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopRequest, _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::EulerAngle, _impl_.roll_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _impl_.pitch_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _impl_.yaw_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopResponse, _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::CaptureInfo, _impl_.position_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.attitude_quaternion_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.attitude_euler_angle_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.time_utc_us_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.is_success_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.index_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.file_url_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomStopResponse, _impl_.camera_result_), 0, - 1, - 2, - ~0u, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeRequest, _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::ZoomRangeRequest, _impl_.range_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::ZoomRangeResponse, _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::ZoomRangeResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _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::TrackPointRequest, _impl_.point_x_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _impl_.point_y_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointRequest, _impl_.radius_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackPointResponse, _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::TrackPointResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleRequest, _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::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_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleRequest, _impl_.bottom_right_y_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackRectangleResponse, _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::TrackRectangleResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackStopRequest, _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::TrackStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::TrackStopResponse, _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::TrackStopResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusInStartRequest, _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::FocusInStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusInStartResponse, _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::FocusInStartResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusOutStartRequest, _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::FocusOutStartResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusOutStartResponse, _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::FocusOutStartResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusStopRequest, _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::FocusStopResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusStopResponse, _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::FocusStopResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeRequest, _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::FocusRangeRequest, _impl_.range_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::FocusRangeResponse, _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::FocusRangeResponse, _impl_.camera_result_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraResult, _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::CameraResult, _impl_.result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CameraResult, _impl_.result_str_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _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::Position, _impl_.latitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.longitude_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.absolute_altitude_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Position, _impl_.relative_altitude_m_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _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::Quaternion, _impl_.w_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.x_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.y_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::Quaternion, _impl_.z_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _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::EulerAngle, _impl_.roll_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _impl_.pitch_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::EulerAngle, _impl_.yaw_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _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::CaptureInfo, _impl_.position_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.attitude_quaternion_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.attitude_euler_angle_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.time_utc_us_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.is_success_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.index_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::CaptureInfo, _impl_.file_url_), + 0, + 1, + 2, + ~0u, ~0u, ~0u, ~0u, @@ -1699,18 +2280,40 @@ static const ::_pbi::MigrationSchema {381, -1, -1, sizeof(::mavsdk::rpc::camera::SelectCameraRequest)}, {390, -1, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsRequest)}, {398, 407, -1, sizeof(::mavsdk::rpc::camera::ResetSettingsResponse)}, - {408, -1, -1, sizeof(::mavsdk::rpc::camera::CameraResult)}, - {418, -1, -1, sizeof(::mavsdk::rpc::camera::Position)}, - {430, -1, -1, sizeof(::mavsdk::rpc::camera::Quaternion)}, - {442, -1, -1, sizeof(::mavsdk::rpc::camera::EulerAngle)}, - {453, 468, -1, sizeof(::mavsdk::rpc::camera::CaptureInfo)}, - {475, -1, -1, sizeof(::mavsdk::rpc::camera::VideoStreamSettings)}, - {490, 501, -1, sizeof(::mavsdk::rpc::camera::VideoStreamInfo)}, - {504, -1, -1, sizeof(::mavsdk::rpc::camera::Status)}, - {522, -1, -1, sizeof(::mavsdk::rpc::camera::Option)}, - {532, 544, -1, sizeof(::mavsdk::rpc::camera::Setting)}, - {548, -1, -1, sizeof(::mavsdk::rpc::camera::SettingOptions)}, - {560, -1, -1, sizeof(::mavsdk::rpc::camera::Information)}, + {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)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -1758,6 +2361,28 @@ static const ::_pb::Message* const file_default_instances[] = { &::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, + &::mavsdk::rpc::camera::_ZoomInStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomOutStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomOutStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomStopRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomStopResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomRangeRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_ZoomRangeResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackPointRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackPointResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackRectangleRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackRectangleResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackStopRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_TrackStopResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusInStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusInStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusOutStartRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusOutStartResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusStopRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusStopResponse_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusRangeRequest_default_instance_._instance, + &::mavsdk::rpc::camera::_FocusRangeResponse_default_instance_._instance, &::mavsdk::rpc::camera::_CameraResult_default_instance_._instance, &::mavsdk::rpc::camera::_Position_default_instance_._instance, &::mavsdk::rpc::camera::_Quaternion_default_instance_._instance, @@ -1840,137 +2465,195 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "meraResult\"(\n\023SelectCameraRequest\022\021\n\tcam" "era_id\030\001 \001(\005\"\026\n\024ResetSettingsRequest\"O\n\025" "ResetSettingsResponse\0226\n\rcamera_result\030\001" - " \001(\0132\037.mavsdk.rpc.camera.CameraResult\"\301\002" - "\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.mavsdk." - "rpc.camera.CameraResult.Result\022\022\n\nresult" - "_str\030\002 \001(\t\"\344\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020" - "\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN_PROGR" - "ESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_DENIED\020" - "\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022" - "\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_" - "SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPPORTED\020" - "\t\"q\n\010Position\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rl" - "ongitude_deg\030\002 \001(\001\022\033\n\023absolute_altitude_" - "m\030\003 \001(\002\022\033\n\023relative_altitude_m\030\004 \001(\002\"8\n\n" - "Quaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 " - "\001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n\010roll_deg" - "\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001" - "(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030\001 \001(\0132\033.m" - "avsdk.rpc.camera.Position\022:\n\023attitude_qu" - "aternion\030\002 \001(\0132\035.mavsdk.rpc.camera.Quate" - "rnion\022;\n\024attitude_euler_angle\030\003 \001(\0132\035.ma" - "vsdk.rpc.camera.EulerAngle\022\023\n\013time_utc_u" - "s\030\004 \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005index\030\006 \001" - "(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoStreamSett" - "ings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031horizonta" - "l_resolution_pix\030\002 \001(\r\022\037\n\027vertical_resol" - "ution_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s\030\004 \001(\r\022\024\n" - "\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(\t\022\032\n\022hori" - "zontal_fov_deg\030\007 \001(\002\"\302\003\n\017VideoStreamInfo" - "\0228\n\010settings\030\001 \001(\0132&.mavsdk.rpc.camera.V" - "ideoStreamSettings\022D\n\006status\030\002 \001(\01624.mav" - "sdk.rpc.camera.VideoStreamInfo.VideoStre" - "amStatus\022H\n\010spectrum\030\003 \001(\01626.mavsdk.rpc." - "camera.VideoStreamInfo.VideoStreamSpectr" - "um\"]\n\021VideoStreamStatus\022#\n\037VIDEO_STREAM_" - "STATUS_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STA" - "TUS_IN_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectru" - "m\022!\n\035VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#" - "VIDEO_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n" - "\036VIDEO_STREAM_SPECTRUM_INFRARED\020\002\"\207\005\n\006St" - "atus\022\020\n\010video_on\030\001 \001(\010\022\031\n\021photo_interval" - "_on\030\002 \001(\010\022\030\n\020used_storage_mib\030\003 \001(\002\022\035\n\025a" - "vailable_storage_mib\030\004 \001(\002\022\031\n\021total_stor" - "age_mib\030\005 \001(\002\022\030\n\020recording_time_s\030\006 \001(\002\022" - "\031\n\021media_folder_name\030\007 \001(\t\022\?\n\016storage_st" - "atus\030\010 \001(\0162\'.mavsdk.rpc.camera.Status.St" - "orageStatus\022\022\n\nstorage_id\030\t \001(\r\022;\n\014stora" - "ge_type\030\n \001(\0162%.mavsdk.rpc.camera.Status" - ".StorageType\"\221\001\n\rStorageStatus\022 \n\034STORAG" - "E_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORAGE_STAT" - "US_UNFORMATTED\020\001\022\034\n\030STORAGE_STATUS_FORMA" - "TTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPPORTED\020\003" - "\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_UNKNOWN" - "\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n\017STORAG" - "E_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICROSD\020\003\022\023\n" - "\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYPE_OTHER" - "\020\376\001\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022\032\n\022opti" - "on_description\030\002 \001(\t\"w\n\007Setting\022\022\n\nsetti" - "ng_id\030\001 \001(\t\022\033\n\023setting_description\030\002 \001(\t" - "\022)\n\006option\030\003 \001(\0132\031.mavsdk.rpc.camera.Opt" - "ion\022\020\n\010is_range\030\004 \001(\010\"\177\n\016SettingOptions\022" - "\022\n\nsetting_id\030\001 \001(\t\022\033\n\023setting_descripti" - "on\030\002 \001(\t\022*\n\007options\030\003 \003(\0132\031.mavsdk.rpc.c" - "amera.Option\022\020\n\010is_range\030\004 \001(\010\"\325\001\n\013Infor" - "mation\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_nam" - "e\030\002 \001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031hori" - "zontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_" - "sensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resol" - "ution_px\030\006 \001(\r\022\036\n\026vertical_resolution_px" - "\030\007 \001(\r*8\n\004Mode\022\020\n\014MODE_UNKNOWN\020\000\022\016\n\nMODE" - "_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013PhotosRange\022" - "\024\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTOS_RANGE_SI" - "NCE_CONNECTION\020\0012\271\022\n\rCameraService\022R\n\007Pr" - "epare\022!.mavsdk.rpc.camera.PrepareRequest" - "\032\".mavsdk.rpc.camera.PrepareResponse\"\000\022X" - "\n\tTakePhoto\022#.mavsdk.rpc.camera.TakePhot" - "oRequest\032$.mavsdk.rpc.camera.TakePhotoRe" - "sponse\"\000\022s\n\022StartPhotoInterval\022,.mavsdk." - "rpc.camera.StartPhotoIntervalRequest\032-.m" - "avsdk.rpc.camera.StartPhotoIntervalRespo" - "nse\"\000\022p\n\021StopPhotoInterval\022+.mavsdk.rpc." - "camera.StopPhotoIntervalRequest\032,.mavsdk" - ".rpc.camera.StopPhotoIntervalResponse\"\000\022" - "[\n\nStartVideo\022$.mavsdk.rpc.camera.StartV" - "ideoRequest\032%.mavsdk.rpc.camera.StartVid" - "eoResponse\"\000\022X\n\tStopVideo\022#.mavsdk.rpc.c" - "amera.StopVideoRequest\032$.mavsdk.rpc.came" - "ra.StopVideoResponse\"\000\022z\n\023StartVideoStre" - "aming\022-.mavsdk.rpc.camera.StartVideoStre" - "amingRequest\032..mavsdk.rpc.camera.StartVi" - "deoStreamingResponse\"\004\200\265\030\001\022w\n\022StopVideoS" - "treaming\022,.mavsdk.rpc.camera.StopVideoSt" - "reamingRequest\032-.mavsdk.rpc.camera.StopV" - "ideoStreamingResponse\"\004\200\265\030\001\022R\n\007SetMode\022!" - ".mavsdk.rpc.camera.SetModeRequest\032\".mavs" - "dk.rpc.camera.SetModeResponse\"\000\022[\n\nListP" - "hotos\022$.mavsdk.rpc.camera.ListPhotosRequ" - "est\032%.mavsdk.rpc.camera.ListPhotosRespon" - "se\"\000\022]\n\rSubscribeMode\022\'.mavsdk.rpc.camer" - "a.SubscribeModeRequest\032\037.mavsdk.rpc.came" - "ra.ModeResponse\"\0000\001\022r\n\024SubscribeInformat" - "ion\022..mavsdk.rpc.camera.SubscribeInforma" - "tionRequest\032&.mavsdk.rpc.camera.Informat" - "ionResponse\"\0000\001\022~\n\030SubscribeVideoStreamI" - "nfo\0222.mavsdk.rpc.camera.SubscribeVideoSt" - "reamInfoRequest\032*.mavsdk.rpc.camera.Vide" - "oStreamInfoResponse\"\0000\001\022v\n\024SubscribeCapt" - "ureInfo\022..mavsdk.rpc.camera.SubscribeCap" - "tureInfoRequest\032&.mavsdk.rpc.camera.Capt" - "ureInfoResponse\"\004\200\265\030\0000\001\022c\n\017SubscribeStat" - "us\022).mavsdk.rpc.camera.SubscribeStatusRe" - "quest\032!.mavsdk.rpc.camera.StatusResponse" - "\"\0000\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavs" - "dk.rpc.camera.SubscribeCurrentSettingsRe" - "quest\032*.mavsdk.rpc.camera.CurrentSetting" - "sResponse\"\004\200\265\030\0000\001\022\223\001\n\037SubscribePossibleS" - "ettingOptions\0229.mavsdk.rpc.camera.Subscr" - "ibePossibleSettingOptionsRequest\0321.mavsd" - "k.rpc.camera.PossibleSettingOptionsRespo" - "nse\"\0000\001\022[\n\nSetSetting\022$.mavsdk.rpc.camer" - "a.SetSettingRequest\032%.mavsdk.rpc.camera." - "SetSettingResponse\"\000\022[\n\nGetSetting\022$.mav" - "sdk.rpc.camera.GetSettingRequest\032%.mavsd" - "k.rpc.camera.GetSettingResponse\"\000\022d\n\rFor" - "matStorage\022\'.mavsdk.rpc.camera.FormatSto" - "rageRequest\032(.mavsdk.rpc.camera.FormatSt" - "orageResponse\"\000\022e\n\014SelectCamera\022&.mavsdk" - ".rpc.camera.SelectCameraRequest\032\'.mavsdk" - ".rpc.camera.SelectCameraResponse\"\004\200\265\030\001\022d" - "\n\rResetSettings\022\'.mavsdk.rpc.camera.Rese" - "tSettingsRequest\032(.mavsdk.rpc.camera.Res" - "etSettingsResponse\"\000B\037\n\020io.mavsdk.camera" - "B\013CameraProtob\006proto3" + " \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" + "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" + "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" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -1980,13 +2663,13 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 7941, + 10256, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, descriptor_table_camera_2fcamera_2eproto_deps, 1, - 56, + 78, schemas, file_default_instances, TableStruct_camera_2fcamera_2eproto::offsets, @@ -8004,14 +8687,3463 @@ FormatStorageResponse::~FormatStorageResponse() { _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FormatStorageResponse::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[39]); +} +// =================================================================== + +class SelectCameraResponse::_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) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SelectCameraResponse) +} +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) +} +inline PROTOBUF_NDEBUG_INLINE SelectCameraResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void SelectCameraResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +SelectCameraResponse::~SelectCameraResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SelectCameraResponse::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_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* SelectCameraResponse::_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> SelectCameraResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _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), + &_SelectCameraResponse_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_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, + }}, {{ + }}, +}; + +::uint8_t* SelectCameraResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.SelectCameraResponse) + ::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.SelectCameraResponse) + return target; +} + +::size_t SelectCameraResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraResponse) + ::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 SelectCameraResponse::_class_data_ = { + SelectCameraResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SelectCameraResponse::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) + 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 SelectCameraResponse::CopyFrom(const SelectCameraResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.SelectCameraResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SelectCameraResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SelectCameraResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SelectCameraResponse::InternalSwap(SelectCameraResponse* 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 SelectCameraResponse::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 { + public: +}; + +SelectCameraRequest::SelectCameraRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.SelectCameraRequest) +} +SelectCameraRequest::SelectCameraRequest( + ::google::protobuf::Arena* arena, const SelectCameraRequest& from) + : SelectCameraRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE SelectCameraRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void SelectCameraRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_id_ = {}; +} +SelectCameraRequest::~SelectCameraRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SelectCameraRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void SelectCameraRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.SelectCameraRequest) + 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* SelectCameraRequest::_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> SelectCameraRequest::_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 + &_SelectCameraRequest_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_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 camera_id = 1; + {PROTOBUF_FIELD_OFFSET(SelectCameraRequest, _impl_.camera_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* SelectCameraRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.SelectCameraRequest) + ::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.SelectCameraRequest) + return target; +} + +::size_t SelectCameraRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraRequest) + ::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 SelectCameraRequest::_class_data_ = { + SelectCameraRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SelectCameraRequest::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) + 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 SelectCameraRequest::CopyFrom(const SelectCameraRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.SelectCameraRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SelectCameraRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SelectCameraRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SelectCameraRequest::InternalSwap(SelectCameraRequest* 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 { + 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 { + 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[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 { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[44]); +} +// =================================================================== + +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[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) +} + + + + + + + + + +::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[46]); +} +// =================================================================== + +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[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 { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[48]); +} +// =================================================================== + +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[49]); +} +// =================================================================== + +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); + _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; + + _impl_.range_ = 0; + _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<0, 1, 0, 0, 2> ZoomRangeRequest::_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 + &_ZoomRangeRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // float range = 1; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(ZoomRangeRequest, _impl_.range_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // float range = 1; + {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; + + // float range = 1; + 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( + 1, 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; + + // float range = 1; + 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; + + 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_); + swap(_impl_.range_, other->_impl_.range_); +} + +::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[50]); +} +// =================================================================== + +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[51]); +} +// =================================================================== + +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} {} + +inline void TrackPointRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, point_x_), + 0, + offsetof(Impl_, radius_) - + offsetof(Impl_, point_x_) + + 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; + + ::memset(&_impl_.point_x_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.radius_) - + reinterpret_cast(&_impl_.point_x_)) + sizeof(_impl_.radius_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* TrackPointRequest::_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<2, 3, 0, 0, 2> TrackPointRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 3, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967288, // skipmap + offsetof(decltype(_table_), field_entries), + 3, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_TrackPointRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // float point_x = 1; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_)}}, + // float point_y = 2; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_)}}, + // float radius = 3; + {::_pbi::TcParser::FastF32S1, + {29, 63, 0, PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // float point_x = 1; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_x_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float point_y = 2; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.point_y_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float radius = 3; + {PROTOBUF_FIELD_OFFSET(TrackPointRequest, _impl_.radius_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* TrackPointRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // float point_x = 1; + 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) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_point_x(), target); + } + + // float point_y = 2; + 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( + 2, this->_internal_point_y(), target); + } + + // float radius = 3; + 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( + 3, this->_internal_radius(), 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.TrackPointRequest) + return target; +} + +::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 point_x = 1; + 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) { + total_size += 5; + } + + // float point_y = 2; + 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 = 3; + 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 TrackPointRequest::_class_data_ = { + TrackPointRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* TrackPointRequest::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) + 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_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 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 TrackPointRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* TrackPointRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void TrackPointRequest::InternalSwap(TrackPointRequest* 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_)); +} + +::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[52]); +} +// =================================================================== + +class TrackPointResponse::_Internal { + public: + 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); + 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) { + return *msg->_impl_.camera_result_; +} +TrackPointResponse::TrackPointResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackPointResponse) +} +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} {} + +TrackPointResponse::TrackPointResponse( + ::google::protobuf::Arena* arena, + const TrackPointResponse& from) + : ::google::protobuf::Message(arena) { + TrackPointResponse* 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.TrackPointResponse) +} +inline PROTOBUF_NDEBUG_INLINE TrackPointResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void TrackPointResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +TrackPointResponse::~TrackPointResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackPointResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void TrackPointResponse::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_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* TrackPointResponse::_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> TrackPointResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(TrackPointResponse, _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), + &_TrackPointResponse_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_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {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>()}, + }}, {{ + }}, +}; + +::uint8_t* TrackPointResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackPointResponse) + ::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.TrackPointResponse) + return target; +} + +::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; + // 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 TrackPointResponse::_class_data_ = { + TrackPointResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* TrackPointResponse::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) + 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 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 TrackPointResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* TrackPointResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +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 TrackPointResponse::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 TrackRectangleRequest::_Internal { + public: +}; + +TrackRectangleRequest::TrackRectangleRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleRequest) +} +TrackRectangleRequest::TrackRectangleRequest( + ::google::protobuf::Arena* arena, const TrackRectangleRequest& from) + : TrackRectangleRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE TrackRectangleRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void TrackRectangleRequest::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_)); +} +TrackRectangleRequest::~TrackRectangleRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void TrackRectangleRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +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_.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_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* TrackRectangleRequest::_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<2, 4, 0, 0, 2> TrackRectangleRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 4, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967280, // skipmap + offsetof(decltype(_table_), field_entries), + 4, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_TrackRectangleRequest_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_)}}, + }}, {{ + 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)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* TrackRectangleRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleRequest) + ::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); + } + + 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.TrackRectangleRequest) + 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()); + } + 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 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 TrackRectangleRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* TrackRectangleRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void TrackRectangleRequest::InternalSwap(TrackRectangleRequest* 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_)); +} + +::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[54]); +} +// =================================================================== + +class TrackRectangleResponse::_Internal { + public: + 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); + 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) { + return *msg->_impl_.camera_result_; +} +TrackRectangleResponse::TrackRectangleResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackRectangleResponse) +} +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} {} + +TrackRectangleResponse::TrackRectangleResponse( + ::google::protobuf::Arena* arena, + const TrackRectangleResponse& from) + : ::google::protobuf::Message(arena) { + TrackRectangleResponse* 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.TrackRectangleResponse) +} +inline PROTOBUF_NDEBUG_INLINE TrackRectangleResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void TrackRectangleResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +TrackRectangleResponse::~TrackRectangleResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackRectangleResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void TrackRectangleResponse::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_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* TrackRectangleResponse::_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> TrackRectangleResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(TrackRectangleResponse, _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), + &_TrackRectangleResponse_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_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {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>()}, + }}, {{ + }}, +}; + +::uint8_t* TrackRectangleResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.TrackRectangleResponse) + ::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.TrackRectangleResponse) + return target; +} + +::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; + // 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 TrackRectangleResponse::_class_data_ = { + TrackRectangleResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* TrackRectangleResponse::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) + 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 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 TrackRectangleResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* TrackRectangleResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +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 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) +} + + + + + + + + + +::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[56]); +} +// =================================================================== + +class TrackStopResponse::_Internal { + public: + 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); + 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) { + return *msg->_impl_.camera_result_; +} +TrackStopResponse::TrackStopResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.TrackStopResponse) +} +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} {} + +TrackStopResponse::TrackStopResponse( + ::google::protobuf::Arena* arena, + const TrackStopResponse& from) + : ::google::protobuf::Message(arena) { + TrackStopResponse* 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.TrackStopResponse) +} +inline PROTOBUF_NDEBUG_INLINE TrackStopResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void TrackStopResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +TrackStopResponse::~TrackStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.TrackStopResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void TrackStopResponse::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_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* TrackStopResponse::_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> TrackStopResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(TrackStopResponse, _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), + &_TrackStopResponse_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_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {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>()}, + }}, {{ + }}, +}; + +::uint8_t* TrackStopResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@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[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 { + return ::_pbi::AssignDescriptors( + &descriptor_table_camera_2fcamera_2eproto_getter, &descriptor_table_camera_2fcamera_2eproto_once, + file_level_metadata_camera_2fcamera_2eproto[58]); +} +// =================================================================== + +class FocusInStartResponse::_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) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusInStartResponse) +} +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) +} +inline PROTOBUF_NDEBUG_INLINE FocusInStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FocusInStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +FocusInStartResponse::~FocusInStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusInStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FocusInStartResponse::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_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* FocusInStartResponse::_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> FocusInStartResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(FocusInStartResponse, _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), + &_FocusInStartResponse_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_)}}, + }}, {{ + 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>()}, + }}, {{ + }}, +}; + +::uint8_t* FocusInStartResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.camera.FocusInStartResponse) + ::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.FocusInStartResponse) + return target; +} + +::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; + // 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 FocusInStartResponse::_class_data_ = { + FocusInStartResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* FocusInStartResponse::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) + 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 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 FocusInStartResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* FocusInStartResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +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 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) +} + + + + + + + + + +::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]); +} +// =================================================================== + +class FocusOutStartResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(FocusOutStartResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FocusOutStartResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::camera::CameraResult& FocusOutStartResponse::_Internal::camera_result(const FocusOutStartResponse* msg) { + return *msg->_impl_.camera_result_; +} +FocusOutStartResponse::FocusOutStartResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.camera.FocusOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE FocusOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +FocusOutStartResponse::FocusOutStartResponse( + ::google::protobuf::Arena* arena, + const FocusOutStartResponse& from) + : ::google::protobuf::Message(arena) { + FocusOutStartResponse* 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.FocusOutStartResponse) +} +inline PROTOBUF_NDEBUG_INLINE FocusOutStartResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void FocusOutStartResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.camera_result_ = {}; +} +FocusOutStartResponse::~FocusOutStartResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusOutStartResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void FocusOutStartResponse::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_NOINLINE void FocusOutStartResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusOutStartResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8026,7 +12158,7 @@ PROTOBUF_NOINLINE void FormatStorageResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FormatStorageResponse::_InternalParse( +const char* FocusOutStartResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8034,9 +12166,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> FocusOutStartResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(FocusOutStartResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8045,17 +12177,17 @@ 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, + &_FocusOutStartResponse_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_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FocusOutStartResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(FormatStorageResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(FocusOutStartResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -8063,10 +12195,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FormatStorageResponse::_table_ = { }}, }; -::uint8_t* FormatStorageResponse::_InternalSerialize( +::uint8_t* FocusOutStartResponse::_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.FocusOutStartResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8083,12 +12215,12 @@ ::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.FocusOutStartResponse) return target; } -::size_t FormatStorageResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FormatStorageResponse) +::size_t FocusOutStartResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusOutStartResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8105,18 +12237,18 @@ ::size_t FormatStorageResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FormatStorageResponse::_class_data_ = { - FormatStorageResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FocusOutStartResponse::_class_data_ = { + FocusOutStartResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FormatStorageResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusOutStartResponse::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 FocusOutStartResponse::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.FocusOutStartResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8128,64 +12260,99 @@ void FormatStorageResponse::MergeImpl(::google::protobuf::Message& to_msg, const _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 FocusOutStartResponse::CopyFrom(const FocusOutStartResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusOutStartResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FormatStorageResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusOutStartResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* FormatStorageResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusOutStartResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void FormatStorageResponse::InternalSwap(FormatStorageResponse* PROTOBUF_RESTRICT other) { +void FocusOutStartResponse::InternalSwap(FocusOutStartResponse* 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 { +::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[39]); + file_level_metadata_camera_2fcamera_2eproto[61]); } // =================================================================== -class SelectCameraResponse::_Internal { +class FocusStopRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); +}; + +FocusStopRequest::FocusStopRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(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_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusStopRequest) +} + + + + + + + + + +::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]); +} +// =================================================================== + +class FocusStopResponse::_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); + 8 * PROTOBUF_FIELD_OFFSET(FocusStopResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FocusStopResponse* 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) { +const ::mavsdk::rpc::camera::CameraResult& FocusStopResponse::_Internal::camera_result(const FocusStopResponse* msg) { return *msg->_impl_.camera_result_; } -SelectCameraResponse::SelectCameraResponse(::google::protobuf::Arena* arena) +FocusStopResponse::FocusStopResponse(::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.FocusStopResponse) } -inline PROTOBUF_NDEBUG_INLINE SelectCameraResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SelectCameraResponse::SelectCameraResponse( +FocusStopResponse::FocusStopResponse( ::google::protobuf::Arena* arena, - const SelectCameraResponse& from) + const FocusStopResponse& from) : ::google::protobuf::Message(arena) { - SelectCameraResponse* const _this = this; + FocusStopResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8195,30 +12362,30 @@ SelectCameraResponse::SelectCameraResponse( ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.SelectCameraResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera.FocusStopResponse) } -inline PROTOBUF_NDEBUG_INLINE SelectCameraResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusStopResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SelectCameraResponse::SharedCtor(::_pb::Arena* arena) { +inline void FocusStopResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -SelectCameraResponse::~SelectCameraResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraResponse) +FocusStopResponse::~FocusStopResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusStopResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SelectCameraResponse::SharedDtor() { +inline void FocusStopResponse::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 FocusStopResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusStopResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8233,7 +12400,7 @@ PROTOBUF_NOINLINE void SelectCameraResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SelectCameraResponse::_InternalParse( +const char* FocusStopResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8241,9 +12408,9 @@ 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, 1, 0, 2> FocusStopResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(FocusStopResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8252,17 +12419,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SelectCameraResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SelectCameraResponse_default_instance_._instance, + &_FocusStopResponse_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_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FocusStopResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.camera.CameraResult camera_result = 1; - {PROTOBUF_FIELD_OFFSET(SelectCameraResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(FocusStopResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -8270,10 +12437,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SelectCameraResponse::_table_ = { }}, }; -::uint8_t* SelectCameraResponse::_InternalSerialize( +::uint8_t* FocusStopResponse::_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.FocusStopResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8290,12 +12457,12 @@ ::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.FocusStopResponse) return target; } -::size_t SelectCameraResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraResponse) +::size_t FocusStopResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusStopResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8312,18 +12479,18 @@ ::size_t SelectCameraResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SelectCameraResponse::_class_data_ = { - SelectCameraResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FocusStopResponse::_class_data_ = { + FocusStopResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SelectCameraResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusStopResponse::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 FocusStopResponse::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.FocusStopResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8335,79 +12502,79 @@ void SelectCameraResponse::MergeImpl(::google::protobuf::Message& to_msg, const _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 FocusStopResponse::CopyFrom(const FocusStopResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusStopResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SelectCameraResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusStopResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SelectCameraResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusStopResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SelectCameraResponse::InternalSwap(SelectCameraResponse* PROTOBUF_RESTRICT other) { +void FocusStopResponse::InternalSwap(FocusStopResponse* 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 SelectCameraResponse::GetMetadata() const { +::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[40]); + file_level_metadata_camera_2fcamera_2eproto[63]); } // =================================================================== -class SelectCameraRequest::_Internal { +class FocusRangeRequest::_Internal { public: }; -SelectCameraRequest::SelectCameraRequest(::google::protobuf::Arena* arena) +FocusRangeRequest::FocusRangeRequest(::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.FocusRangeRequest) } -SelectCameraRequest::SelectCameraRequest( - ::google::protobuf::Arena* arena, const SelectCameraRequest& from) - : SelectCameraRequest(arena) { +FocusRangeRequest::FocusRangeRequest( + ::google::protobuf::Arena* arena, const FocusRangeRequest& from) + : FocusRangeRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SelectCameraRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusRangeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SelectCameraRequest::SharedCtor(::_pb::Arena* arena) { +inline void FocusRangeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.camera_id_ = {}; + _impl_.range_ = {}; } -SelectCameraRequest::~SelectCameraRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.SelectCameraRequest) +FocusRangeRequest::~FocusRangeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusRangeRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SelectCameraRequest::SharedDtor() { +inline void FocusRangeRequest::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 FocusRangeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusRangeRequest) 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; + _impl_.range_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SelectCameraRequest::_InternalParse( +const char* FocusRangeRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8415,7 +12582,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> FocusRangeRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -8426,36 +12593,41 @@ 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, + &_FocusRangeRequest_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_)}}, + // float range = 1; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_)}}, }}, {{ 65535, 65535 }}, {{ - // int32 camera_id = 1; - {PROTOBUF_FIELD_OFFSET(SelectCameraRequest, _impl_.camera_id_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float range = 1; + {PROTOBUF_FIELD_OFFSET(FocusRangeRequest, _impl_.range_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries {{ }}, }; -::uint8_t* SelectCameraRequest::_InternalSerialize( +::uint8_t* FocusRangeRequest::_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.FocusRangeRequest) ::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 = 1; + 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( + 1, this->_internal_range(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8463,141 +12635,115 @@ ::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.FocusRangeRequest) return target; } -::size_t SelectCameraRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.SelectCameraRequest) +::size_t FocusRangeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusRangeRequest) ::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 = 1; + 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 SelectCameraRequest::_class_data_ = { - SelectCameraRequest::MergeImpl, +const ::google::protobuf::Message::ClassData FocusRangeRequest::_class_data_ = { + FocusRangeRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SelectCameraRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusRangeRequest::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 FocusRangeRequest::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.FocusRangeRequest) 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 SelectCameraRequest::CopyFrom(const SelectCameraRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.SelectCameraRequest) +void FocusRangeRequest::CopyFrom(const FocusRangeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusRangeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SelectCameraRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusRangeRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SelectCameraRequest::AccessCachedSize() const { +::_pbi::CachedSize* FocusRangeRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SelectCameraRequest::InternalSwap(SelectCameraRequest* PROTOBUF_RESTRICT other) { +void FocusRangeRequest::InternalSwap(FocusRangeRequest* 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 { - 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) + swap(_impl_.range_, other->_impl_.range_); } - - - - - - - - -::google::protobuf::Metadata ResetSettingsRequest::GetMetadata() const { +::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[42]); + file_level_metadata_camera_2fcamera_2eproto[64]); } // =================================================================== -class ResetSettingsResponse::_Internal { +class FocusRangeResponse::_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(FocusRangeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const FocusRangeResponse* 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& FocusRangeResponse::_Internal::camera_result(const FocusRangeResponse* msg) { return *msg->_impl_.camera_result_; } -ResetSettingsResponse::ResetSettingsResponse(::google::protobuf::Arena* arena) +FocusRangeResponse::FocusRangeResponse(::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.FocusRangeResponse) } -inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusRangeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ResetSettingsResponse::ResetSettingsResponse( +FocusRangeResponse::FocusRangeResponse( ::google::protobuf::Arena* arena, - const ResetSettingsResponse& from) + const FocusRangeResponse& from) : ::google::protobuf::Message(arena) { - ResetSettingsResponse* const _this = this; + FocusRangeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8607,30 +12753,30 @@ 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.FocusRangeResponse) } -inline PROTOBUF_NDEBUG_INLINE ResetSettingsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FocusRangeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ResetSettingsResponse::SharedCtor(::_pb::Arena* arena) { +inline void FocusRangeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.camera_result_ = {}; } -ResetSettingsResponse::~ResetSettingsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.ResetSettingsResponse) +FocusRangeResponse::~FocusRangeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.camera.FocusRangeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ResetSettingsResponse::SharedDtor() { +inline void FocusRangeResponse::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 FocusRangeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.camera.FocusRangeResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8645,7 +12791,7 @@ PROTOBUF_NOINLINE void ResetSettingsResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ResetSettingsResponse::_InternalParse( +const char* FocusRangeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8653,9 +12799,9 @@ const char* ResetSettingsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ResetSettingsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FocusRangeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ResetSettingsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(FocusRangeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8664,17 +12810,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ResetSettingsResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ResetSettingsResponse_default_instance_._instance, + &_FocusRangeResponse_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_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FocusRangeResponse, _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(FocusRangeResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::camera::CameraResult>()}, @@ -8682,10 +12828,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ResetSettingsResponse::_table_ = { }}, }; -::uint8_t* ResetSettingsResponse::_InternalSerialize( +::uint8_t* FocusRangeResponse::_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.FocusRangeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8702,12 +12848,12 @@ ::uint8_t* ResetSettingsResponse::_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.ResetSettingsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.camera.FocusRangeResponse) return target; } -::size_t ResetSettingsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.ResetSettingsResponse) +::size_t FocusRangeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.camera.FocusRangeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8724,18 +12870,18 @@ ::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 FocusRangeResponse::_class_data_ = { + FocusRangeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ResetSettingsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FocusRangeResponse::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 FocusRangeResponse::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.FocusRangeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8747,31 +12893,31 @@ 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 FocusRangeResponse::CopyFrom(const FocusRangeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.camera.FocusRangeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ResetSettingsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FocusRangeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ResetSettingsResponse::AccessCachedSize() const { +::_pbi::CachedSize* FocusRangeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ResetSettingsResponse::InternalSwap(ResetSettingsResponse* PROTOBUF_RESTRICT other) { +void FocusRangeResponse::InternalSwap(FocusRangeResponse* 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 { +::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[43]); + file_level_metadata_camera_2fcamera_2eproto[65]); } // =================================================================== @@ -8987,7 +13133,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[44]); + file_level_metadata_camera_2fcamera_2eproto[66]); } // =================================================================== @@ -9291,7 +13437,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[45]); + file_level_metadata_camera_2fcamera_2eproto[67]); } // =================================================================== @@ -9595,7 +13741,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[46]); + file_level_metadata_camera_2fcamera_2eproto[68]); } // =================================================================== @@ -9864,7 +14010,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[47]); + file_level_metadata_camera_2fcamera_2eproto[69]); } // =================================================================== @@ -10275,7 +14421,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[48]); + file_level_metadata_camera_2fcamera_2eproto[70]); } // =================================================================== @@ -10648,7 +14794,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[49]); + file_level_metadata_camera_2fcamera_2eproto[71]); } // =================================================================== @@ -10920,7 +15066,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[50]); + file_level_metadata_camera_2fcamera_2eproto[72]); } // =================================================================== @@ -11390,7 +15536,7 @@ void Status::InternalSwap(Status* PROTOBUF_RESTRICT other) { ::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[51]); + file_level_metadata_camera_2fcamera_2eproto[73]); } // =================================================================== @@ -11609,7 +15755,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[52]); + file_level_metadata_camera_2fcamera_2eproto[74]); } // =================================================================== @@ -11911,7 +16057,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[53]); + file_level_metadata_camera_2fcamera_2eproto[75]); } // =================================================================== @@ -12181,7 +16327,7 @@ void SettingOptions::InternalSwap(SettingOptions* PROTOBUF_RESTRICT other) { ::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[54]); + file_level_metadata_camera_2fcamera_2eproto[76]); } // =================================================================== @@ -12575,7 +16721,7 @@ 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[55]); + file_level_metadata_camera_2fcamera_2eproto[77]); } // @@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 eabc9a72cc..201b3abdc8 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -76,6 +76,30 @@ extern CurrentSettingsResponseDefaultTypeInternal _CurrentSettingsResponse_defau class EulerAngle; struct EulerAngleDefaultTypeInternal; extern EulerAngleDefaultTypeInternal _EulerAngle_default_instance_; +class FocusInStartRequest; +struct FocusInStartRequestDefaultTypeInternal; +extern FocusInStartRequestDefaultTypeInternal _FocusInStartRequest_default_instance_; +class FocusInStartResponse; +struct FocusInStartResponseDefaultTypeInternal; +extern FocusInStartResponseDefaultTypeInternal _FocusInStartResponse_default_instance_; +class FocusOutStartRequest; +struct FocusOutStartRequestDefaultTypeInternal; +extern FocusOutStartRequestDefaultTypeInternal _FocusOutStartRequest_default_instance_; +class FocusOutStartResponse; +struct FocusOutStartResponseDefaultTypeInternal; +extern FocusOutStartResponseDefaultTypeInternal _FocusOutStartResponse_default_instance_; +class FocusRangeRequest; +struct FocusRangeRequestDefaultTypeInternal; +extern FocusRangeRequestDefaultTypeInternal _FocusRangeRequest_default_instance_; +class FocusRangeResponse; +struct FocusRangeResponseDefaultTypeInternal; +extern FocusRangeResponseDefaultTypeInternal _FocusRangeResponse_default_instance_; +class FocusStopRequest; +struct FocusStopRequestDefaultTypeInternal; +extern FocusStopRequestDefaultTypeInternal _FocusStopRequest_default_instance_; +class FocusStopResponse; +struct FocusStopResponseDefaultTypeInternal; +extern FocusStopResponseDefaultTypeInternal _FocusStopResponse_default_instance_; class FormatStorageRequest; struct FormatStorageRequestDefaultTypeInternal; extern FormatStorageRequestDefaultTypeInternal _FormatStorageRequest_default_instance_; @@ -220,6 +244,24 @@ extern TakePhotoRequestDefaultTypeInternal _TakePhotoRequest_default_instance_; class TakePhotoResponse; struct TakePhotoResponseDefaultTypeInternal; extern TakePhotoResponseDefaultTypeInternal _TakePhotoResponse_default_instance_; +class TrackPointRequest; +struct TrackPointRequestDefaultTypeInternal; +extern TrackPointRequestDefaultTypeInternal _TrackPointRequest_default_instance_; +class TrackPointResponse; +struct TrackPointResponseDefaultTypeInternal; +extern TrackPointResponseDefaultTypeInternal _TrackPointResponse_default_instance_; +class TrackRectangleRequest; +struct TrackRectangleRequestDefaultTypeInternal; +extern TrackRectangleRequestDefaultTypeInternal _TrackRectangleRequest_default_instance_; +class TrackRectangleResponse; +struct TrackRectangleResponseDefaultTypeInternal; +extern TrackRectangleResponseDefaultTypeInternal _TrackRectangleResponse_default_instance_; +class TrackStopRequest; +struct TrackStopRequestDefaultTypeInternal; +extern TrackStopRequestDefaultTypeInternal _TrackStopRequest_default_instance_; +class TrackStopResponse; +struct TrackStopResponseDefaultTypeInternal; +extern TrackStopResponseDefaultTypeInternal _TrackStopResponse_default_instance_; class VideoStreamInfo; struct VideoStreamInfoDefaultTypeInternal; extern VideoStreamInfoDefaultTypeInternal _VideoStreamInfo_default_instance_; @@ -229,6 +271,30 @@ extern VideoStreamInfoResponseDefaultTypeInternal _VideoStreamInfoResponse_defau class VideoStreamSettings; struct VideoStreamSettingsDefaultTypeInternal; extern VideoStreamSettingsDefaultTypeInternal _VideoStreamSettings_default_instance_; +class ZoomInStartRequest; +struct ZoomInStartRequestDefaultTypeInternal; +extern ZoomInStartRequestDefaultTypeInternal _ZoomInStartRequest_default_instance_; +class ZoomInStartResponse; +struct ZoomInStartResponseDefaultTypeInternal; +extern ZoomInStartResponseDefaultTypeInternal _ZoomInStartResponse_default_instance_; +class ZoomOutStartRequest; +struct ZoomOutStartRequestDefaultTypeInternal; +extern ZoomOutStartRequestDefaultTypeInternal _ZoomOutStartRequest_default_instance_; +class ZoomOutStartResponse; +struct ZoomOutStartResponseDefaultTypeInternal; +extern ZoomOutStartResponseDefaultTypeInternal _ZoomOutStartResponse_default_instance_; +class ZoomRangeRequest; +struct ZoomRangeRequestDefaultTypeInternal; +extern ZoomRangeRequestDefaultTypeInternal _ZoomRangeRequest_default_instance_; +class ZoomRangeResponse; +struct ZoomRangeResponseDefaultTypeInternal; +extern ZoomRangeResponseDefaultTypeInternal _ZoomRangeResponse_default_instance_; +class ZoomStopRequest; +struct ZoomStopRequestDefaultTypeInternal; +extern ZoomStopRequestDefaultTypeInternal _ZoomStopRequest_default_instance_; +class ZoomStopResponse; +struct ZoomStopResponseDefaultTypeInternal; +extern ZoomStopResponseDefaultTypeInternal _ZoomStopResponse_default_instance_; } // namespace camera } // namespace rpc } // namespace mavsdk @@ -487,26 +553,25 @@ inline bool PhotosRange_Parse(absl::string_view name, PhotosRange* value) { // ------------------------------------------------------------------- -class VideoStreamSettings final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.VideoStreamSettings) */ { +class ZoomStopRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomStopRequest) */ { public: - inline VideoStreamSettings() : VideoStreamSettings(nullptr) {} - ~VideoStreamSettings() override; + inline ZoomStopRequest() : ZoomStopRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR VideoStreamSettings(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomStopRequest(::google::protobuf::internal::ConstantInitialized); - inline VideoStreamSettings(const VideoStreamSettings& from) - : VideoStreamSettings(nullptr, from) {} - VideoStreamSettings(VideoStreamSettings&& from) noexcept - : VideoStreamSettings() { + inline ZoomStopRequest(const ZoomStopRequest& from) + : ZoomStopRequest(nullptr, from) {} + ZoomStopRequest(ZoomStopRequest&& from) noexcept + : ZoomStopRequest() { *this = ::std::move(from); } - inline VideoStreamSettings& operator=(const VideoStreamSettings& from) { + inline ZoomStopRequest& operator=(const ZoomStopRequest& from) { CopyFrom(from); return *this; } - inline VideoStreamSettings& operator=(VideoStreamSettings&& from) noexcept { + inline ZoomStopRequest& operator=(ZoomStopRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -538,20 +603,20 @@ class VideoStreamSettings final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const VideoStreamSettings& default_instance() { + static const ZoomStopRequest& default_instance() { return *internal_default_instance(); } - static inline const VideoStreamSettings* internal_default_instance() { - return reinterpret_cast( - &_VideoStreamSettings_default_instance_); + static inline const ZoomStopRequest* internal_default_instance() { + return reinterpret_cast( + &_ZoomStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 48; - friend void swap(VideoStreamSettings& a, VideoStreamSettings& b) { + friend void swap(ZoomStopRequest& a, ZoomStopRequest& b) { a.Swap(&b); } - inline void Swap(VideoStreamSettings* other) { + inline void Swap(ZoomStopRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -564,7 +629,7 @@ class VideoStreamSettings final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(VideoStreamSettings* other) { + void UnsafeArenaSwap(ZoomStopRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -572,146 +637,39 @@ class VideoStreamSettings final : // implements Message ---------------------------------------------- - VideoStreamSettings* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ZoomStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const VideoStreamSettings& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const VideoStreamSettings& from) { - VideoStreamSettings::MergeImpl(*this, from); + 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); } - 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(VideoStreamSettings* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.VideoStreamSettings"; + return "mavsdk.rpc.camera.ZoomStopRequest"; } protected: - explicit VideoStreamSettings(::google::protobuf::Arena* arena); - VideoStreamSettings(::google::protobuf::Arena* arena, const VideoStreamSettings& from); + explicit ZoomStopRequest(::google::protobuf::Arena* arena); + 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 { - kUriFieldNumber = 6, - kFrameRateHzFieldNumber = 1, - kHorizontalResolutionPixFieldNumber = 2, - kVerticalResolutionPixFieldNumber = 3, - kBitRateBSFieldNumber = 4, - kRotationDegFieldNumber = 5, - kHorizontalFovDegFieldNumber = 7, - }; - // string uri = 6; - void clear_uri() ; - const std::string& uri() const; - template - void set_uri(Arg_&& arg, Args_... args); - std::string* mutable_uri(); - PROTOBUF_NODISCARD std::string* release_uri(); - void set_allocated_uri(std::string* value); - - private: - const std::string& _internal_uri() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_uri( - const std::string& value); - std::string* _internal_mutable_uri(); - - public: - // float frame_rate_hz = 1; - void clear_frame_rate_hz() ; - float frame_rate_hz() const; - void set_frame_rate_hz(float value); - - private: - float _internal_frame_rate_hz() const; - void _internal_set_frame_rate_hz(float value); - - public: - // uint32 horizontal_resolution_pix = 2; - void clear_horizontal_resolution_pix() ; - ::uint32_t horizontal_resolution_pix() const; - void set_horizontal_resolution_pix(::uint32_t value); - - private: - ::uint32_t _internal_horizontal_resolution_pix() const; - void _internal_set_horizontal_resolution_pix(::uint32_t value); - - public: - // uint32 vertical_resolution_pix = 3; - void clear_vertical_resolution_pix() ; - ::uint32_t vertical_resolution_pix() const; - void set_vertical_resolution_pix(::uint32_t value); - - private: - ::uint32_t _internal_vertical_resolution_pix() const; - void _internal_set_vertical_resolution_pix(::uint32_t value); - - public: - // uint32 bit_rate_b_s = 4; - void clear_bit_rate_b_s() ; - ::uint32_t bit_rate_b_s() const; - void set_bit_rate_b_s(::uint32_t value); - - private: - ::uint32_t _internal_bit_rate_b_s() const; - void _internal_set_bit_rate_b_s(::uint32_t value); - - public: - // uint32 rotation_deg = 5; - void clear_rotation_deg() ; - ::uint32_t rotation_deg() const; - void set_rotation_deg(::uint32_t value); - - private: - ::uint32_t _internal_rotation_deg() const; - void _internal_set_rotation_deg(::uint32_t value); - - public: - // float horizontal_fov_deg = 7; - void clear_horizontal_fov_deg() ; - float horizontal_fov_deg() const; - void set_horizontal_fov_deg(float value); - - private: - float _internal_horizontal_fov_deg() const; - void _internal_set_horizontal_fov_deg(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.VideoStreamSettings) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomStopRequest) private: class _Internal; - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 3, 7, 0, - 49, 2> - _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -726,39 +684,31 @@ class VideoStreamSettings final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::ArenaStringPtr uri_; - float frame_rate_hz_; - ::uint32_t horizontal_resolution_pix_; - ::uint32_t vertical_resolution_pix_; - ::uint32_t bit_rate_b_s_; - ::uint32_t rotation_deg_; - float horizontal_fov_deg_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class TakePhotoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TakePhotoRequest) */ { +class ZoomRangeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomRangeRequest) */ { public: - inline TakePhotoRequest() : TakePhotoRequest(nullptr) {} + inline ZoomRangeRequest() : ZoomRangeRequest(nullptr) {} + ~ZoomRangeRequest() override; template - explicit PROTOBUF_CONSTEXPR TakePhotoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomRangeRequest(::google::protobuf::internal::ConstantInitialized); - inline TakePhotoRequest(const TakePhotoRequest& from) - : TakePhotoRequest(nullptr, from) {} - TakePhotoRequest(TakePhotoRequest&& from) noexcept - : TakePhotoRequest() { + inline ZoomRangeRequest(const ZoomRangeRequest& from) + : ZoomRangeRequest(nullptr, from) {} + ZoomRangeRequest(ZoomRangeRequest&& from) noexcept + : ZoomRangeRequest() { *this = ::std::move(from); } - inline TakePhotoRequest& operator=(const TakePhotoRequest& from) { + inline ZoomRangeRequest& operator=(const ZoomRangeRequest& from) { CopyFrom(from); return *this; } - inline TakePhotoRequest& operator=(TakePhotoRequest&& from) noexcept { + inline ZoomRangeRequest& operator=(ZoomRangeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -790,20 +740,20 @@ class TakePhotoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const TakePhotoRequest& default_instance() { + static const ZoomRangeRequest& default_instance() { return *internal_default_instance(); } - static inline const TakePhotoRequest* internal_default_instance() { - return reinterpret_cast( - &_TakePhotoRequest_default_instance_); + static inline const ZoomRangeRequest* internal_default_instance() { + return reinterpret_cast( + &_ZoomRangeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 50; - friend void swap(TakePhotoRequest& a, TakePhotoRequest& b) { + friend void swap(ZoomRangeRequest& a, ZoomRangeRequest& b) { a.Swap(&b); } - inline void Swap(TakePhotoRequest* other) { + inline void Swap(ZoomRangeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -816,7 +766,7 @@ class TakePhotoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(TakePhotoRequest* other) { + void UnsafeArenaSwap(ZoomRangeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -824,39 +774,74 @@ class TakePhotoRequest final : // implements Message ---------------------------------------------- - 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); + ZoomRangeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - 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 ZoomRangeRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ZoomRangeRequest& from) { + ZoomRangeRequest::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(ZoomRangeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.TakePhotoRequest"; + return "mavsdk.rpc.camera.ZoomRangeRequest"; } protected: - explicit TakePhotoRequest(::google::protobuf::Arena* arena); - TakePhotoRequest(::google::protobuf::Arena* arena, const TakePhotoRequest& from); + explicit ZoomRangeRequest(::google::protobuf::Arena* arena); + ZoomRangeRequest(::google::protobuf::Arena* arena, const ZoomRangeRequest& 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.TakePhotoRequest) + enum : int { + kRangeFieldNumber = 1, + }; + // float range = 1; + void clear_range() ; + float range() const; + void set_range(float value); + + private: + float _internal_range() const; + void _internal_set_range(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomRangeRequest) 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 @@ -871,30 +856,33 @@ class TakePhotoRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + float range_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeVideoStreamInfoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) */ { +class ZoomOutStartRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomOutStartRequest) */ { public: - inline SubscribeVideoStreamInfoRequest() : SubscribeVideoStreamInfoRequest(nullptr) {} + inline ZoomOutStartRequest() : ZoomOutStartRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeVideoStreamInfoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomOutStartRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeVideoStreamInfoRequest(const SubscribeVideoStreamInfoRequest& from) - : SubscribeVideoStreamInfoRequest(nullptr, from) {} - SubscribeVideoStreamInfoRequest(SubscribeVideoStreamInfoRequest&& from) noexcept - : SubscribeVideoStreamInfoRequest() { + inline ZoomOutStartRequest(const ZoomOutStartRequest& from) + : ZoomOutStartRequest(nullptr, from) {} + ZoomOutStartRequest(ZoomOutStartRequest&& from) noexcept + : ZoomOutStartRequest() { *this = ::std::move(from); } - inline SubscribeVideoStreamInfoRequest& operator=(const SubscribeVideoStreamInfoRequest& from) { + inline ZoomOutStartRequest& operator=(const ZoomOutStartRequest& from) { CopyFrom(from); return *this; } - inline SubscribeVideoStreamInfoRequest& operator=(SubscribeVideoStreamInfoRequest&& from) noexcept { + inline ZoomOutStartRequest& operator=(ZoomOutStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -926,20 +914,20 @@ class SubscribeVideoStreamInfoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeVideoStreamInfoRequest& default_instance() { + static const ZoomOutStartRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeVideoStreamInfoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeVideoStreamInfoRequest_default_instance_); + static inline const ZoomOutStartRequest* internal_default_instance() { + return reinterpret_cast( + &_ZoomOutStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 46; - friend void swap(SubscribeVideoStreamInfoRequest& a, SubscribeVideoStreamInfoRequest& b) { + friend void swap(ZoomOutStartRequest& a, ZoomOutStartRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeVideoStreamInfoRequest* other) { + inline void Swap(ZoomOutStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -952,7 +940,7 @@ class SubscribeVideoStreamInfoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeVideoStreamInfoRequest* other) { + void UnsafeArenaSwap(ZoomOutStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -960,15 +948,15 @@ class SubscribeVideoStreamInfoRequest final : // implements Message ---------------------------------------------- - SubscribeVideoStreamInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ZoomOutStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeVideoStreamInfoRequest& from) { + inline void CopyFrom(const ZoomOutStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeVideoStreamInfoRequest& from) { + void MergeFrom(const ZoomOutStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -976,11 +964,11 @@ class SubscribeVideoStreamInfoRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest"; + return "mavsdk.rpc.camera.ZoomOutStartRequest"; } protected: - explicit SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena); - SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena, const SubscribeVideoStreamInfoRequest& from); + explicit ZoomOutStartRequest(::google::protobuf::Arena* arena); + ZoomOutStartRequest(::google::protobuf::Arena* arena, const ZoomOutStartRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -989,7 +977,7 @@ class SubscribeVideoStreamInfoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomOutStartRequest) private: class _Internal; @@ -1012,25 +1000,25 @@ class SubscribeVideoStreamInfoRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeStatusRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeStatusRequest) */ { +class ZoomInStartRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ZoomInStartRequest) */ { public: - inline SubscribeStatusRequest() : SubscribeStatusRequest(nullptr) {} + inline ZoomInStartRequest() : ZoomInStartRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ZoomInStartRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeStatusRequest(const SubscribeStatusRequest& from) - : SubscribeStatusRequest(nullptr, from) {} - SubscribeStatusRequest(SubscribeStatusRequest&& from) noexcept - : SubscribeStatusRequest() { + inline ZoomInStartRequest(const ZoomInStartRequest& from) + : ZoomInStartRequest(nullptr, from) {} + ZoomInStartRequest(ZoomInStartRequest&& from) noexcept + : ZoomInStartRequest() { *this = ::std::move(from); } - inline SubscribeStatusRequest& operator=(const SubscribeStatusRequest& from) { + inline ZoomInStartRequest& operator=(const ZoomInStartRequest& from) { CopyFrom(from); return *this; } - inline SubscribeStatusRequest& operator=(SubscribeStatusRequest&& from) noexcept { + inline ZoomInStartRequest& operator=(ZoomInStartRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1062,20 +1050,20 @@ class SubscribeStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeStatusRequest& default_instance() { + static const ZoomInStartRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeStatusRequest_default_instance_); + static inline const ZoomInStartRequest* internal_default_instance() { + return reinterpret_cast( + &_ZoomInStartRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 44; - friend void swap(SubscribeStatusRequest& a, SubscribeStatusRequest& b) { + friend void swap(ZoomInStartRequest& a, ZoomInStartRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeStatusRequest* other) { + inline void Swap(ZoomInStartRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1088,7 +1076,7 @@ class SubscribeStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeStatusRequest* other) { + void UnsafeArenaSwap(ZoomInStartRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1096,15 +1084,15 @@ class SubscribeStatusRequest final : // implements Message ---------------------------------------------- - SubscribeStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ZoomInStartRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeStatusRequest& from) { + inline void CopyFrom(const ZoomInStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeStatusRequest& from) { + void MergeFrom(const ZoomInStartRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1112,11 +1100,11 @@ class SubscribeStatusRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeStatusRequest"; + return "mavsdk.rpc.camera.ZoomInStartRequest"; } protected: - explicit SubscribeStatusRequest(::google::protobuf::Arena* arena); - SubscribeStatusRequest(::google::protobuf::Arena* arena, const SubscribeStatusRequest& from); + explicit ZoomInStartRequest(::google::protobuf::Arena* arena); + ZoomInStartRequest(::google::protobuf::Arena* arena, const ZoomInStartRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1125,7 +1113,7 @@ class SubscribeStatusRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ZoomInStartRequest) private: class _Internal; @@ -1148,25 +1136,26 @@ class SubscribeStatusRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribePossibleSettingOptionsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest) */ { +class VideoStreamSettings final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.VideoStreamSettings) */ { public: - inline SubscribePossibleSettingOptionsRequest() : SubscribePossibleSettingOptionsRequest(nullptr) {} + inline VideoStreamSettings() : VideoStreamSettings(nullptr) {} + ~VideoStreamSettings() override; template - explicit PROTOBUF_CONSTEXPR SubscribePossibleSettingOptionsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR VideoStreamSettings(::google::protobuf::internal::ConstantInitialized); - inline SubscribePossibleSettingOptionsRequest(const SubscribePossibleSettingOptionsRequest& from) - : SubscribePossibleSettingOptionsRequest(nullptr, from) {} - SubscribePossibleSettingOptionsRequest(SubscribePossibleSettingOptionsRequest&& from) noexcept - : SubscribePossibleSettingOptionsRequest() { + inline VideoStreamSettings(const VideoStreamSettings& from) + : VideoStreamSettings(nullptr, from) {} + VideoStreamSettings(VideoStreamSettings&& from) noexcept + : VideoStreamSettings() { *this = ::std::move(from); } - inline SubscribePossibleSettingOptionsRequest& operator=(const SubscribePossibleSettingOptionsRequest& from) { + inline VideoStreamSettings& operator=(const VideoStreamSettings& from) { CopyFrom(from); return *this; } - inline SubscribePossibleSettingOptionsRequest& operator=(SubscribePossibleSettingOptionsRequest&& from) noexcept { + inline VideoStreamSettings& operator=(VideoStreamSettings&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1198,20 +1187,20 @@ class SubscribePossibleSettingOptionsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribePossibleSettingOptionsRequest& default_instance() { + static const VideoStreamSettings& default_instance() { return *internal_default_instance(); } - static inline const SubscribePossibleSettingOptionsRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribePossibleSettingOptionsRequest_default_instance_); + static inline const VideoStreamSettings* internal_default_instance() { + return reinterpret_cast( + &_VideoStreamSettings_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 71; - friend void swap(SubscribePossibleSettingOptionsRequest& a, SubscribePossibleSettingOptionsRequest& b) { + friend void swap(VideoStreamSettings& a, VideoStreamSettings& b) { a.Swap(&b); } - inline void Swap(SubscribePossibleSettingOptionsRequest* other) { + inline void Swap(VideoStreamSettings* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1224,7 +1213,7 @@ class SubscribePossibleSettingOptionsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribePossibleSettingOptionsRequest* other) { + void UnsafeArenaSwap(VideoStreamSettings* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1232,39 +1221,146 @@ class SubscribePossibleSettingOptionsRequest final : // implements Message ---------------------------------------------- - SubscribePossibleSettingOptionsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribePossibleSettingOptionsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + VideoStreamSettings* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribePossibleSettingOptionsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const VideoStreamSettings& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const VideoStreamSettings& from) { + VideoStreamSettings::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(VideoStreamSettings* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest"; + return "mavsdk.rpc.camera.VideoStreamSettings"; } protected: - explicit SubscribePossibleSettingOptionsRequest(::google::protobuf::Arena* arena); - SubscribePossibleSettingOptionsRequest(::google::protobuf::Arena* arena, const SubscribePossibleSettingOptionsRequest& from); + explicit VideoStreamSettings(::google::protobuf::Arena* arena); + VideoStreamSettings(::google::protobuf::Arena* arena, const VideoStreamSettings& 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.SubscribePossibleSettingOptionsRequest) + enum : int { + kUriFieldNumber = 6, + kFrameRateHzFieldNumber = 1, + kHorizontalResolutionPixFieldNumber = 2, + kVerticalResolutionPixFieldNumber = 3, + kBitRateBSFieldNumber = 4, + kRotationDegFieldNumber = 5, + kHorizontalFovDegFieldNumber = 7, + }; + // string uri = 6; + void clear_uri() ; + const std::string& uri() const; + template + void set_uri(Arg_&& arg, Args_... args); + std::string* mutable_uri(); + PROTOBUF_NODISCARD std::string* release_uri(); + void set_allocated_uri(std::string* value); + + private: + const std::string& _internal_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_uri( + const std::string& value); + std::string* _internal_mutable_uri(); + + public: + // float frame_rate_hz = 1; + void clear_frame_rate_hz() ; + float frame_rate_hz() const; + void set_frame_rate_hz(float value); + + private: + float _internal_frame_rate_hz() const; + void _internal_set_frame_rate_hz(float value); + + public: + // uint32 horizontal_resolution_pix = 2; + void clear_horizontal_resolution_pix() ; + ::uint32_t horizontal_resolution_pix() const; + void set_horizontal_resolution_pix(::uint32_t value); + + private: + ::uint32_t _internal_horizontal_resolution_pix() const; + void _internal_set_horizontal_resolution_pix(::uint32_t value); + + public: + // uint32 vertical_resolution_pix = 3; + void clear_vertical_resolution_pix() ; + ::uint32_t vertical_resolution_pix() const; + void set_vertical_resolution_pix(::uint32_t value); + + private: + ::uint32_t _internal_vertical_resolution_pix() const; + void _internal_set_vertical_resolution_pix(::uint32_t value); + + public: + // uint32 bit_rate_b_s = 4; + void clear_bit_rate_b_s() ; + ::uint32_t bit_rate_b_s() const; + void set_bit_rate_b_s(::uint32_t value); + + private: + ::uint32_t _internal_bit_rate_b_s() const; + void _internal_set_bit_rate_b_s(::uint32_t value); + + public: + // uint32 rotation_deg = 5; + void clear_rotation_deg() ; + ::uint32_t rotation_deg() const; + void set_rotation_deg(::uint32_t value); + + private: + ::uint32_t _internal_rotation_deg() const; + void _internal_set_rotation_deg(::uint32_t value); + + public: + // float horizontal_fov_deg = 7; + void clear_horizontal_fov_deg() ; + float horizontal_fov_deg() const; + void set_horizontal_fov_deg(float value); + + private: + float _internal_horizontal_fov_deg() const; + void _internal_set_horizontal_fov_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.VideoStreamSettings) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 7, 0, + 49, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1279,30 +1375,39 @@ class SubscribePossibleSettingOptionsRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr uri_; + float frame_rate_hz_; + ::uint32_t horizontal_resolution_pix_; + ::uint32_t vertical_resolution_pix_; + ::uint32_t bit_rate_b_s_; + ::uint32_t rotation_deg_; + float horizontal_fov_deg_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeModeRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeModeRequest) */ { +class TrackStopRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TrackStopRequest) */ { public: - inline SubscribeModeRequest() : SubscribeModeRequest(nullptr) {} + inline TrackStopRequest() : TrackStopRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeModeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TrackStopRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeModeRequest(const SubscribeModeRequest& from) - : SubscribeModeRequest(nullptr, from) {} - SubscribeModeRequest(SubscribeModeRequest&& from) noexcept - : SubscribeModeRequest() { + inline TrackStopRequest(const TrackStopRequest& from) + : TrackStopRequest(nullptr, from) {} + TrackStopRequest(TrackStopRequest&& from) noexcept + : TrackStopRequest() { *this = ::std::move(from); } - inline SubscribeModeRequest& operator=(const SubscribeModeRequest& from) { + inline TrackStopRequest& operator=(const TrackStopRequest& from) { CopyFrom(from); return *this; } - inline SubscribeModeRequest& operator=(SubscribeModeRequest&& from) noexcept { + inline TrackStopRequest& operator=(TrackStopRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1334,20 +1439,20 @@ class SubscribeModeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeModeRequest& default_instance() { + static const TrackStopRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeModeRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeModeRequest_default_instance_); + static inline const TrackStopRequest* internal_default_instance() { + return reinterpret_cast( + &_TrackStopRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 56; - friend void swap(SubscribeModeRequest& a, SubscribeModeRequest& b) { + friend void swap(TrackStopRequest& a, TrackStopRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeModeRequest* other) { + inline void Swap(TrackStopRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1360,7 +1465,7 @@ class SubscribeModeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeModeRequest* other) { + void UnsafeArenaSwap(TrackStopRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1368,15 +1473,15 @@ class SubscribeModeRequest final : // implements Message ---------------------------------------------- - SubscribeModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + TrackStopRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeModeRequest& from) { + inline void CopyFrom(const TrackStopRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeModeRequest& from) { + void MergeFrom(const TrackStopRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1384,11 +1489,11 @@ class SubscribeModeRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeModeRequest"; + return "mavsdk.rpc.camera.TrackStopRequest"; } protected: - explicit SubscribeModeRequest(::google::protobuf::Arena* arena); - SubscribeModeRequest(::google::protobuf::Arena* arena, const SubscribeModeRequest& from); + explicit TrackStopRequest(::google::protobuf::Arena* arena); + TrackStopRequest(::google::protobuf::Arena* arena, const TrackStopRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1397,7 +1502,7 @@ class SubscribeModeRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeModeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TrackStopRequest) private: class _Internal; @@ -1420,25 +1525,26 @@ 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 TrackRectangleRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TrackRectangleRequest) */ { public: - inline SubscribeInformationRequest() : SubscribeInformationRequest(nullptr) {} + inline TrackRectangleRequest() : TrackRectangleRequest(nullptr) {} + ~TrackRectangleRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeInformationRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TrackRectangleRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeInformationRequest(const SubscribeInformationRequest& from) - : SubscribeInformationRequest(nullptr, from) {} - SubscribeInformationRequest(SubscribeInformationRequest&& from) noexcept - : SubscribeInformationRequest() { + inline TrackRectangleRequest(const TrackRectangleRequest& from) + : TrackRectangleRequest(nullptr, from) {} + TrackRectangleRequest(TrackRectangleRequest&& from) noexcept + : TrackRectangleRequest() { *this = ::std::move(from); } - inline SubscribeInformationRequest& operator=(const SubscribeInformationRequest& from) { + inline TrackRectangleRequest& operator=(const TrackRectangleRequest& from) { CopyFrom(from); return *this; } - inline SubscribeInformationRequest& operator=(SubscribeInformationRequest&& from) noexcept { + inline TrackRectangleRequest& operator=(TrackRectangleRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1470,20 +1576,20 @@ class SubscribeInformationRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeInformationRequest& default_instance() { + static const TrackRectangleRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeInformationRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeInformationRequest_default_instance_); + static inline const TrackRectangleRequest* internal_default_instance() { + return reinterpret_cast( + &_TrackRectangleRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 54; - friend void swap(SubscribeInformationRequest& a, SubscribeInformationRequest& b) { + friend void swap(TrackRectangleRequest& a, TrackRectangleRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeInformationRequest* other) { + inline void Swap(TrackRectangleRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1496,7 +1602,7 @@ class SubscribeInformationRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeInformationRequest* other) { + void UnsafeArenaSwap(TrackRectangleRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1504,39 +1610,107 @@ class SubscribeInformationRequest final : // implements Message ---------------------------------------------- - SubscribeInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeInformationRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + TrackRectangleRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeInformationRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const TrackRectangleRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const TrackRectangleRequest& from) { + TrackRectangleRequest::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: + ::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(TrackRectangleRequest* other); + + private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeInformationRequest"; + return "mavsdk.rpc.camera.TrackRectangleRequest"; } protected: - explicit SubscribeInformationRequest(::google::protobuf::Arena* arena); - SubscribeInformationRequest(::google::protobuf::Arena* arena, const SubscribeInformationRequest& from); + explicit TrackRectangleRequest(::google::protobuf::Arena* arena); + TrackRectangleRequest(::google::protobuf::Arena* arena, const TrackRectangleRequest& 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.SubscribeInformationRequest) + enum : int { + kTopLeftXFieldNumber = 1, + kTopLeftYFieldNumber = 2, + kBottomRightXFieldNumber = 3, + kBottomRightYFieldNumber = 4, + }; + // float top_left_x = 1; + void clear_top_left_x() ; + float top_left_x() const; + void set_top_left_x(float value); + + private: + float _internal_top_left_x() const; + void _internal_set_top_left_x(float value); + + public: + // float top_left_y = 2; + void clear_top_left_y() ; + float top_left_y() const; + void set_top_left_y(float value); + + private: + float _internal_top_left_y() const; + void _internal_set_top_left_y(float value); + + public: + // float bottom_right_x = 3; + void clear_bottom_right_x() ; + float bottom_right_x() const; + void set_bottom_right_x(float value); + + private: + float _internal_bottom_right_x() const; + void _internal_set_bottom_right_x(float value); + + public: + // float bottom_right_y = 4; + void clear_bottom_right_y() ; + float bottom_right_y() const; + void set_bottom_right_y(float value); + + private: + float _internal_bottom_right_y() const; + void _internal_set_bottom_right_y(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TrackRectangleRequest) 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 @@ -1551,30 +1725,37 @@ class SubscribeInformationRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + float top_left_x_; + float top_left_y_; + float bottom_right_x_; + float bottom_right_y_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeCurrentSettingsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) */ { +class TrackPointRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TrackPointRequest) */ { public: - inline SubscribeCurrentSettingsRequest() : SubscribeCurrentSettingsRequest(nullptr) {} + inline TrackPointRequest() : TrackPointRequest(nullptr) {} + ~TrackPointRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TrackPointRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCurrentSettingsRequest(const SubscribeCurrentSettingsRequest& from) - : SubscribeCurrentSettingsRequest(nullptr, from) {} - SubscribeCurrentSettingsRequest(SubscribeCurrentSettingsRequest&& from) noexcept - : SubscribeCurrentSettingsRequest() { + inline TrackPointRequest(const TrackPointRequest& from) + : TrackPointRequest(nullptr, from) {} + TrackPointRequest(TrackPointRequest&& from) noexcept + : TrackPointRequest() { *this = ::std::move(from); } - inline SubscribeCurrentSettingsRequest& operator=(const SubscribeCurrentSettingsRequest& from) { + inline TrackPointRequest& operator=(const TrackPointRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCurrentSettingsRequest& operator=(SubscribeCurrentSettingsRequest&& from) noexcept { + inline TrackPointRequest& operator=(TrackPointRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1606,20 +1787,20 @@ class SubscribeCurrentSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCurrentSettingsRequest& default_instance() { + static const TrackPointRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCurrentSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCurrentSettingsRequest_default_instance_); + static inline const TrackPointRequest* internal_default_instance() { + return reinterpret_cast( + &_TrackPointRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 52; - friend void swap(SubscribeCurrentSettingsRequest& a, SubscribeCurrentSettingsRequest& b) { + friend void swap(TrackPointRequest& a, TrackPointRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCurrentSettingsRequest* other) { + inline void Swap(TrackPointRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1632,7 +1813,7 @@ class SubscribeCurrentSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCurrentSettingsRequest* other) { + void UnsafeArenaSwap(TrackPointRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1640,39 +1821,96 @@ class SubscribeCurrentSettingsRequest final : // implements Message ---------------------------------------------- - SubscribeCurrentSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCurrentSettingsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + TrackPointRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCurrentSettingsRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const TrackPointRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const TrackPointRequest& from) { + TrackPointRequest::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(TrackPointRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SubscribeCurrentSettingsRequest"; + return "mavsdk.rpc.camera.TrackPointRequest"; } protected: - explicit SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena); - SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena, const SubscribeCurrentSettingsRequest& from); + explicit TrackPointRequest(::google::protobuf::Arena* arena); + TrackPointRequest(::google::protobuf::Arena* arena, const TrackPointRequest& 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.SubscribeCurrentSettingsRequest) + enum : int { + kPointXFieldNumber = 1, + kPointYFieldNumber = 2, + kRadiusFieldNumber = 3, + }; + // float point_x = 1; + void clear_point_x() ; + float point_x() const; + void set_point_x(float value); + + private: + float _internal_point_x() const; + void _internal_set_point_x(float value); + + public: + // float point_y = 2; + void clear_point_y() ; + float point_y() const; + void set_point_y(float value); + + private: + float _internal_point_y() const; + void _internal_set_point_y(float value); + + public: + // float radius = 3; + void clear_radius() ; + float radius() const; + void set_radius(float value); + + private: + float _internal_radius() const; + void _internal_set_radius(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TrackPointRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 2, 3, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1687,30 +1925,35 @@ class SubscribeCurrentSettingsRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + float point_x_; + float point_y_; + float radius_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SubscribeCaptureInfoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) */ { +class TakePhotoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.TakePhotoRequest) */ { public: - inline SubscribeCaptureInfoRequest() : SubscribeCaptureInfoRequest(nullptr) {} + inline TakePhotoRequest() : TakePhotoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCaptureInfoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TakePhotoRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCaptureInfoRequest(const SubscribeCaptureInfoRequest& from) - : SubscribeCaptureInfoRequest(nullptr, from) {} - SubscribeCaptureInfoRequest(SubscribeCaptureInfoRequest&& from) noexcept - : SubscribeCaptureInfoRequest() { + inline TakePhotoRequest(const TakePhotoRequest& from) + : TakePhotoRequest(nullptr, from) {} + TakePhotoRequest(TakePhotoRequest&& from) noexcept + : TakePhotoRequest() { *this = ::std::move(from); } - inline SubscribeCaptureInfoRequest& operator=(const SubscribeCaptureInfoRequest& from) { + inline TakePhotoRequest& operator=(const TakePhotoRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCaptureInfoRequest& operator=(SubscribeCaptureInfoRequest&& from) noexcept { + inline TakePhotoRequest& operator=(TakePhotoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1742,20 +1985,20 @@ class SubscribeCaptureInfoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCaptureInfoRequest& default_instance() { + static const TakePhotoRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCaptureInfoRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCaptureInfoRequest_default_instance_); + static inline const TakePhotoRequest* internal_default_instance() { + return reinterpret_cast( + &_TakePhotoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 2; - friend void swap(SubscribeCaptureInfoRequest& a, SubscribeCaptureInfoRequest& b) { + friend void swap(TakePhotoRequest& a, TakePhotoRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCaptureInfoRequest* other) { + inline void Swap(TakePhotoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1768,7 +2011,7 @@ class SubscribeCaptureInfoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCaptureInfoRequest* other) { + void UnsafeArenaSwap(TakePhotoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1776,15 +2019,15 @@ class SubscribeCaptureInfoRequest final : // implements Message ---------------------------------------------- - SubscribeCaptureInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + TakePhotoRequest* 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 TakePhotoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCaptureInfoRequest& from) { + void MergeFrom(const TakePhotoRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -1792,11 +2035,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.TakePhotoRequest"; } protected: - explicit SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena); - SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena, const SubscribeCaptureInfoRequest& from); + explicit TakePhotoRequest(::google::protobuf::Arena* arena); + TakePhotoRequest(::google::protobuf::Arena* arena, const TakePhotoRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -1805,7 +2048,7 @@ class SubscribeCaptureInfoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.TakePhotoRequest) private: class _Internal; @@ -1828,26 +2071,25 @@ class SubscribeCaptureInfoRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StopVideoStreamingRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoStreamingRequest) */ { +class SubscribeVideoStreamInfoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) */ { public: - inline StopVideoStreamingRequest() : StopVideoStreamingRequest(nullptr) {} - ~StopVideoStreamingRequest() override; + inline SubscribeVideoStreamInfoRequest() : SubscribeVideoStreamInfoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeVideoStreamInfoRequest(::google::protobuf::internal::ConstantInitialized); - inline StopVideoStreamingRequest(const StopVideoStreamingRequest& from) - : StopVideoStreamingRequest(nullptr, from) {} - StopVideoStreamingRequest(StopVideoStreamingRequest&& from) noexcept - : StopVideoStreamingRequest() { + inline SubscribeVideoStreamInfoRequest(const SubscribeVideoStreamInfoRequest& from) + : SubscribeVideoStreamInfoRequest(nullptr, from) {} + SubscribeVideoStreamInfoRequest(SubscribeVideoStreamInfoRequest&& from) noexcept + : SubscribeVideoStreamInfoRequest() { *this = ::std::move(from); } - inline StopVideoStreamingRequest& operator=(const StopVideoStreamingRequest& from) { + inline SubscribeVideoStreamInfoRequest& operator=(const SubscribeVideoStreamInfoRequest& from) { CopyFrom(from); return *this; } - inline StopVideoStreamingRequest& operator=(StopVideoStreamingRequest&& from) noexcept { + inline SubscribeVideoStreamInfoRequest& operator=(SubscribeVideoStreamInfoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1879,20 +2121,20 @@ class StopVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoStreamingRequest& default_instance() { + static const SubscribeVideoStreamInfoRequest& default_instance() { return *internal_default_instance(); } - static inline const StopVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_StopVideoStreamingRequest_default_instance_); + static inline const SubscribeVideoStreamInfoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeVideoStreamInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 24; - friend void swap(StopVideoStreamingRequest& a, StopVideoStreamingRequest& b) { + friend void swap(SubscribeVideoStreamInfoRequest& a, SubscribeVideoStreamInfoRequest& b) { a.Swap(&b); } - inline void Swap(StopVideoStreamingRequest* other) { + inline void Swap(SubscribeVideoStreamInfoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -1905,7 +2147,7 @@ class StopVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoStreamingRequest* other) { + void UnsafeArenaSwap(SubscribeVideoStreamInfoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -1913,74 +2155,39 @@ class StopVideoStreamingRequest final : // implements Message ---------------------------------------------- - StopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeVideoStreamInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StopVideoStreamingRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StopVideoStreamingRequest& from) { - StopVideoStreamingRequest::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeVideoStreamInfoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeVideoStreamInfoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StopVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StopVideoStreamingRequest"; + return "mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest"; } protected: - explicit StopVideoStreamingRequest(::google::protobuf::Arena* arena); - StopVideoStreamingRequest(::google::protobuf::Arena* arena, const StopVideoStreamingRequest& from); + explicit SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena); + SubscribeVideoStreamInfoRequest(::google::protobuf::Arena* arena, const SubscribeVideoStreamInfoRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - - private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeVideoStreamInfoRequest) 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 @@ -1995,33 +2202,30 @@ class StopVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StopVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoRequest) */ { +class SubscribeStatusRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeStatusRequest) */ { public: - inline StopVideoRequest() : StopVideoRequest(nullptr) {} + inline SubscribeStatusRequest() : SubscribeStatusRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StopVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline StopVideoRequest(const StopVideoRequest& from) - : StopVideoRequest(nullptr, from) {} - StopVideoRequest(StopVideoRequest&& from) noexcept - : StopVideoRequest() { + inline SubscribeStatusRequest(const SubscribeStatusRequest& from) + : SubscribeStatusRequest(nullptr, from) {} + SubscribeStatusRequest(SubscribeStatusRequest&& from) noexcept + : SubscribeStatusRequest() { *this = ::std::move(from); } - inline StopVideoRequest& operator=(const StopVideoRequest& from) { + inline SubscribeStatusRequest& operator=(const SubscribeStatusRequest& from) { CopyFrom(from); return *this; } - inline StopVideoRequest& operator=(StopVideoRequest&& from) noexcept { + inline SubscribeStatusRequest& operator=(SubscribeStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2053,20 +2257,20 @@ class StopVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopVideoRequest& default_instance() { + static const SubscribeStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const StopVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_StopVideoRequest_default_instance_); + static inline const SubscribeStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 28; - friend void swap(StopVideoRequest& a, StopVideoRequest& b) { + friend void swap(SubscribeStatusRequest& a, SubscribeStatusRequest& b) { a.Swap(&b); } - inline void Swap(StopVideoRequest* other) { + inline void Swap(SubscribeStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2079,7 +2283,7 @@ class StopVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopVideoRequest* other) { + void UnsafeArenaSwap(SubscribeStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2087,15 +2291,15 @@ class StopVideoRequest final : // implements Message ---------------------------------------------- - StopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StopVideoRequest& from) { + inline void CopyFrom(const SubscribeStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StopVideoRequest& from) { + void MergeFrom(const SubscribeStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2103,11 +2307,11 @@ class StopVideoRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StopVideoRequest"; + return "mavsdk.rpc.camera.SubscribeStatusRequest"; } protected: - explicit StopVideoRequest(::google::protobuf::Arena* arena); - StopVideoRequest(::google::protobuf::Arena* arena, const StopVideoRequest& from); + explicit SubscribeStatusRequest(::google::protobuf::Arena* arena); + SubscribeStatusRequest(::google::protobuf::Arena* arena, const SubscribeStatusRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2116,7 +2320,7 @@ class StopVideoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopVideoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeStatusRequest) private: class _Internal; @@ -2139,25 +2343,25 @@ class StopVideoRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StopPhotoIntervalRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopPhotoIntervalRequest) */ { +class SubscribePossibleSettingOptionsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest) */ { public: - inline StopPhotoIntervalRequest() : StopPhotoIntervalRequest(nullptr) {} + inline SubscribePossibleSettingOptionsRequest() : SubscribePossibleSettingOptionsRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StopPhotoIntervalRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribePossibleSettingOptionsRequest(::google::protobuf::internal::ConstantInitialized); - inline StopPhotoIntervalRequest(const StopPhotoIntervalRequest& from) - : StopPhotoIntervalRequest(nullptr, from) {} - StopPhotoIntervalRequest(StopPhotoIntervalRequest&& from) noexcept - : StopPhotoIntervalRequest() { + inline SubscribePossibleSettingOptionsRequest(const SubscribePossibleSettingOptionsRequest& from) + : SubscribePossibleSettingOptionsRequest(nullptr, from) {} + SubscribePossibleSettingOptionsRequest(SubscribePossibleSettingOptionsRequest&& from) noexcept + : SubscribePossibleSettingOptionsRequest() { *this = ::std::move(from); } - inline StopPhotoIntervalRequest& operator=(const StopPhotoIntervalRequest& from) { + inline SubscribePossibleSettingOptionsRequest& operator=(const SubscribePossibleSettingOptionsRequest& from) { CopyFrom(from); return *this; } - inline StopPhotoIntervalRequest& operator=(StopPhotoIntervalRequest&& from) noexcept { + inline SubscribePossibleSettingOptionsRequest& operator=(SubscribePossibleSettingOptionsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2189,20 +2393,20 @@ class StopPhotoIntervalRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StopPhotoIntervalRequest& default_instance() { + static const SubscribePossibleSettingOptionsRequest& default_instance() { return *internal_default_instance(); } - static inline const StopPhotoIntervalRequest* internal_default_instance() { - return reinterpret_cast( - &_StopPhotoIntervalRequest_default_instance_); + static inline const SubscribePossibleSettingOptionsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribePossibleSettingOptionsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 32; - friend void swap(StopPhotoIntervalRequest& a, StopPhotoIntervalRequest& b) { + friend void swap(SubscribePossibleSettingOptionsRequest& a, SubscribePossibleSettingOptionsRequest& b) { a.Swap(&b); } - inline void Swap(StopPhotoIntervalRequest* other) { + inline void Swap(SubscribePossibleSettingOptionsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2215,7 +2419,7 @@ class StopPhotoIntervalRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StopPhotoIntervalRequest* other) { + void UnsafeArenaSwap(SubscribePossibleSettingOptionsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2223,15 +2427,15 @@ class StopPhotoIntervalRequest final : // implements Message ---------------------------------------------- - StopPhotoIntervalRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribePossibleSettingOptionsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const StopPhotoIntervalRequest& from) { + inline void CopyFrom(const SubscribePossibleSettingOptionsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StopPhotoIntervalRequest& from) { + void MergeFrom(const SubscribePossibleSettingOptionsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2239,11 +2443,11 @@ class StopPhotoIntervalRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StopPhotoIntervalRequest"; + return "mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest"; } protected: - explicit StopPhotoIntervalRequest(::google::protobuf::Arena* arena); - StopPhotoIntervalRequest(::google::protobuf::Arena* arena, const StopPhotoIntervalRequest& from); + explicit SubscribePossibleSettingOptionsRequest(::google::protobuf::Arena* arena); + SubscribePossibleSettingOptionsRequest(::google::protobuf::Arena* arena, const SubscribePossibleSettingOptionsRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2252,7 +2456,7 @@ class StopPhotoIntervalRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopPhotoIntervalRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribePossibleSettingOptionsRequest) private: class _Internal; @@ -2275,26 +2479,25 @@ class StopPhotoIntervalRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class Status final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Status) */ { +class SubscribeModeRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeModeRequest) */ { public: - inline Status() : Status(nullptr) {} - ~Status() override; + inline SubscribeModeRequest() : SubscribeModeRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR Status(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeModeRequest(::google::protobuf::internal::ConstantInitialized); - inline Status(const Status& from) - : Status(nullptr, from) {} - Status(Status&& from) noexcept - : Status() { + inline SubscribeModeRequest(const SubscribeModeRequest& from) + : SubscribeModeRequest(nullptr, from) {} + SubscribeModeRequest(SubscribeModeRequest&& from) noexcept + : SubscribeModeRequest() { *this = ::std::move(from); } - inline Status& operator=(const Status& from) { + inline SubscribeModeRequest& operator=(const SubscribeModeRequest& from) { CopyFrom(from); return *this; } - inline Status& operator=(Status&& from) noexcept { + inline SubscribeModeRequest& operator=(SubscribeModeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2326,20 +2529,20 @@ class Status final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Status& default_instance() { + static const SubscribeModeRequest& default_instance() { return *internal_default_instance(); } - static inline const Status* internal_default_instance() { - return reinterpret_cast( - &_Status_default_instance_); + static inline const SubscribeModeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 51; + 22; - friend void swap(Status& a, Status& b) { + friend void swap(SubscribeModeRequest& a, SubscribeModeRequest& b) { a.Swap(&b); } - inline void Swap(Status* other) { + inline void Swap(SubscribeModeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2352,7 +2555,7 @@ class Status final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Status* other) { + void UnsafeArenaSwap(SubscribeModeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2360,232 +2563,46 @@ class Status final : // implements Message ---------------------------------------------- - Status* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Status& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Status& from) { - Status::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeModeRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeModeRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(Status* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.Status"; + return "mavsdk.rpc.camera.SubscribeModeRequest"; } protected: - explicit Status(::google::protobuf::Arena* arena); - Status(::google::protobuf::Arena* arena, const Status& from); + explicit SubscribeModeRequest(::google::protobuf::Arena* arena); + SubscribeModeRequest(::google::protobuf::Arena* arena, const SubscribeModeRequest& from); public: - static const ClassData _class_data_; - const ::google::protobuf::Message::ClassData*GetClassData() const final; - ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- - using StorageStatus = Status_StorageStatus; - static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = Status_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; - static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = Status_StorageStatus_STORAGE_STATUS_UNFORMATTED; - static constexpr StorageStatus STORAGE_STATUS_FORMATTED = Status_StorageStatus_STORAGE_STATUS_FORMATTED; - static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = Status_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; - static inline bool StorageStatus_IsValid(int value) { - return Status_StorageStatus_IsValid(value); - } - static constexpr StorageStatus StorageStatus_MIN = Status_StorageStatus_StorageStatus_MIN; - static constexpr StorageStatus StorageStatus_MAX = Status_StorageStatus_StorageStatus_MAX; - static constexpr int StorageStatus_ARRAYSIZE = Status_StorageStatus_StorageStatus_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* StorageStatus_descriptor() { - return Status_StorageStatus_descriptor(); - } - template - static inline const std::string& StorageStatus_Name(T value) { - return Status_StorageStatus_Name(value); - } - static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { - return Status_StorageStatus_Parse(name, value); - } + // accessors ------------------------------------------------------- - using StorageType = Status_StorageType; - static constexpr StorageType STORAGE_TYPE_UNKNOWN = Status_StorageType_STORAGE_TYPE_UNKNOWN; - static constexpr StorageType STORAGE_TYPE_USB_STICK = Status_StorageType_STORAGE_TYPE_USB_STICK; - static constexpr StorageType STORAGE_TYPE_SD = Status_StorageType_STORAGE_TYPE_SD; - static constexpr StorageType STORAGE_TYPE_MICROSD = Status_StorageType_STORAGE_TYPE_MICROSD; - static constexpr StorageType STORAGE_TYPE_HD = Status_StorageType_STORAGE_TYPE_HD; - static constexpr StorageType STORAGE_TYPE_OTHER = Status_StorageType_STORAGE_TYPE_OTHER; - static inline bool StorageType_IsValid(int value) { - return Status_StorageType_IsValid(value); - } - static constexpr StorageType StorageType_MIN = Status_StorageType_StorageType_MIN; - static constexpr StorageType StorageType_MAX = Status_StorageType_StorageType_MAX; - static constexpr int StorageType_ARRAYSIZE = Status_StorageType_StorageType_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* StorageType_descriptor() { - return Status_StorageType_descriptor(); - } - template - static inline const std::string& StorageType_Name(T value) { - return Status_StorageType_Name(value); - } - static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { - return Status_StorageType_Parse(name, value); - } + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeModeRequest) + private: + class _Internal; - // accessors ------------------------------------------------------- - - enum : int { - kMediaFolderNameFieldNumber = 7, - kVideoOnFieldNumber = 1, - kPhotoIntervalOnFieldNumber = 2, - kUsedStorageMibFieldNumber = 3, - kAvailableStorageMibFieldNumber = 4, - kTotalStorageMibFieldNumber = 5, - kRecordingTimeSFieldNumber = 6, - kStorageStatusFieldNumber = 8, - kStorageIdFieldNumber = 9, - kStorageTypeFieldNumber = 10, - }; - // string media_folder_name = 7; - void clear_media_folder_name() ; - const std::string& media_folder_name() const; - template - void set_media_folder_name(Arg_&& arg, Args_... args); - std::string* mutable_media_folder_name(); - PROTOBUF_NODISCARD std::string* release_media_folder_name(); - void set_allocated_media_folder_name(std::string* value); - - private: - const std::string& _internal_media_folder_name() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_media_folder_name( - const std::string& value); - std::string* _internal_mutable_media_folder_name(); - - public: - // bool video_on = 1; - void clear_video_on() ; - bool video_on() const; - void set_video_on(bool value); - - private: - bool _internal_video_on() const; - void _internal_set_video_on(bool value); - - public: - // bool photo_interval_on = 2; - void clear_photo_interval_on() ; - bool photo_interval_on() const; - void set_photo_interval_on(bool value); - - private: - bool _internal_photo_interval_on() const; - void _internal_set_photo_interval_on(bool value); - - public: - // float used_storage_mib = 3; - void clear_used_storage_mib() ; - float used_storage_mib() const; - void set_used_storage_mib(float value); - - private: - float _internal_used_storage_mib() const; - void _internal_set_used_storage_mib(float value); - - public: - // float available_storage_mib = 4; - void clear_available_storage_mib() ; - float available_storage_mib() const; - void set_available_storage_mib(float value); - - private: - float _internal_available_storage_mib() const; - void _internal_set_available_storage_mib(float value); - - public: - // float total_storage_mib = 5; - void clear_total_storage_mib() ; - float total_storage_mib() const; - void set_total_storage_mib(float value); - - private: - float _internal_total_storage_mib() const; - void _internal_set_total_storage_mib(float value); - - public: - // float recording_time_s = 6; - void clear_recording_time_s() ; - float recording_time_s() const; - void set_recording_time_s(float value); - - private: - float _internal_recording_time_s() const; - void _internal_set_recording_time_s(float value); - - public: - // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; - void clear_storage_status() ; - ::mavsdk::rpc::camera::Status_StorageStatus storage_status() const; - void set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); - - private: - ::mavsdk::rpc::camera::Status_StorageStatus _internal_storage_status() const; - void _internal_set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); - - public: - // uint32 storage_id = 9; - void clear_storage_id() ; - ::uint32_t storage_id() const; - void set_storage_id(::uint32_t value); - - private: - ::uint32_t _internal_storage_id() const; - void _internal_set_storage_id(::uint32_t value); - - public: - // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; - void clear_storage_type() ; - ::mavsdk::rpc::camera::Status_StorageType storage_type() const; - void set_storage_type(::mavsdk::rpc::camera::Status_StorageType value); - - private: - ::mavsdk::rpc::camera::Status_StorageType _internal_storage_type() const; - void _internal_set_storage_type(::mavsdk::rpc::camera::Status_StorageType value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Status) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 4, 10, 0, - 58, 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_ { + 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; @@ -2593,43 +2610,30 @@ class Status final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::ArenaStringPtr media_folder_name_; - bool video_on_; - bool photo_interval_on_; - float used_storage_mib_; - float available_storage_mib_; - float total_storage_mib_; - float recording_time_s_; - int storage_status_; - ::uint32_t storage_id_; - int storage_type_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StartVideoStreamingRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoStreamingRequest) */ { +class SubscribeInformationRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeInformationRequest) */ { public: - inline StartVideoStreamingRequest() : StartVideoStreamingRequest(nullptr) {} - ~StartVideoStreamingRequest() override; + inline SubscribeInformationRequest() : SubscribeInformationRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeInformationRequest(::google::protobuf::internal::ConstantInitialized); - inline StartVideoStreamingRequest(const StartVideoStreamingRequest& from) - : StartVideoStreamingRequest(nullptr, from) {} - StartVideoStreamingRequest(StartVideoStreamingRequest&& from) noexcept - : StartVideoStreamingRequest() { + inline SubscribeInformationRequest(const SubscribeInformationRequest& from) + : SubscribeInformationRequest(nullptr, from) {} + SubscribeInformationRequest(SubscribeInformationRequest&& from) noexcept + : SubscribeInformationRequest() { *this = ::std::move(from); } - inline StartVideoStreamingRequest& operator=(const StartVideoStreamingRequest& from) { + inline SubscribeInformationRequest& operator=(const SubscribeInformationRequest& from) { CopyFrom(from); return *this; } - inline StartVideoStreamingRequest& operator=(StartVideoStreamingRequest&& from) noexcept { + inline SubscribeInformationRequest& operator=(SubscribeInformationRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2661,20 +2665,20 @@ class StartVideoStreamingRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoStreamingRequest& default_instance() { + static const SubscribeInformationRequest& default_instance() { return *internal_default_instance(); } - static inline const StartVideoStreamingRequest* internal_default_instance() { - return reinterpret_cast( - &_StartVideoStreamingRequest_default_instance_); + static inline const SubscribeInformationRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeInformationRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 20; - friend void swap(StartVideoStreamingRequest& a, StartVideoStreamingRequest& b) { + friend void swap(SubscribeInformationRequest& a, SubscribeInformationRequest& b) { a.Swap(&b); } - inline void Swap(StartVideoStreamingRequest* other) { + inline void Swap(SubscribeInformationRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2687,7 +2691,7 @@ class StartVideoStreamingRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoStreamingRequest* other) { + void UnsafeArenaSwap(SubscribeInformationRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2695,74 +2699,39 @@ class StartVideoStreamingRequest final : // implements Message ---------------------------------------------- - StartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeInformationRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StartVideoStreamingRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StartVideoStreamingRequest& from) { - StartVideoStreamingRequest::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeInformationRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeInformationRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StartVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StartVideoStreamingRequest"; + return "mavsdk.rpc.camera.SubscribeInformationRequest"; } protected: - explicit StartVideoStreamingRequest(::google::protobuf::Arena* arena); - StartVideoStreamingRequest(::google::protobuf::Arena* arena, const StartVideoStreamingRequest& from); + explicit SubscribeInformationRequest(::google::protobuf::Arena* arena); + SubscribeInformationRequest(::google::protobuf::Arena* arena, const SubscribeInformationRequest& 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 { - kStreamIdFieldNumber = 1, - }; - // int32 stream_id = 1; - void clear_stream_id() ; - ::int32_t stream_id() const; - void set_stream_id(::int32_t value); - - private: - ::int32_t _internal_stream_id() const; - void _internal_set_stream_id(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoStreamingRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeInformationRequest) 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 @@ -2777,33 +2746,30 @@ class StartVideoStreamingRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t stream_id_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StartVideoRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoRequest) */ { +class SubscribeCurrentSettingsRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) */ { public: - inline StartVideoRequest() : StartVideoRequest(nullptr) {} + inline SubscribeCurrentSettingsRequest() : SubscribeCurrentSettingsRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StartVideoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCurrentSettingsRequest(::google::protobuf::internal::ConstantInitialized); - inline StartVideoRequest(const StartVideoRequest& from) - : StartVideoRequest(nullptr, from) {} - StartVideoRequest(StartVideoRequest&& from) noexcept - : StartVideoRequest() { + inline SubscribeCurrentSettingsRequest(const SubscribeCurrentSettingsRequest& from) + : SubscribeCurrentSettingsRequest(nullptr, from) {} + SubscribeCurrentSettingsRequest(SubscribeCurrentSettingsRequest&& from) noexcept + : SubscribeCurrentSettingsRequest() { *this = ::std::move(from); } - inline StartVideoRequest& operator=(const StartVideoRequest& from) { + inline SubscribeCurrentSettingsRequest& operator=(const SubscribeCurrentSettingsRequest& from) { CopyFrom(from); return *this; } - inline StartVideoRequest& operator=(StartVideoRequest&& from) noexcept { + inline SubscribeCurrentSettingsRequest& operator=(SubscribeCurrentSettingsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2835,20 +2801,20 @@ class StartVideoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartVideoRequest& default_instance() { + static const SubscribeCurrentSettingsRequest& default_instance() { return *internal_default_instance(); } - static inline const StartVideoRequest* internal_default_instance() { - return reinterpret_cast( - &_StartVideoRequest_default_instance_); + static inline const SubscribeCurrentSettingsRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCurrentSettingsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 30; - friend void swap(StartVideoRequest& a, StartVideoRequest& b) { + friend void swap(SubscribeCurrentSettingsRequest& a, SubscribeCurrentSettingsRequest& b) { a.Swap(&b); } - inline void Swap(StartVideoRequest* other) { + inline void Swap(SubscribeCurrentSettingsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2861,7 +2827,7 @@ class StartVideoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartVideoRequest* other) { + void UnsafeArenaSwap(SubscribeCurrentSettingsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2869,15 +2835,15 @@ class StartVideoRequest final : // implements Message ---------------------------------------------- - StartVideoRequest* 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 StartVideoRequest& from) { + inline void CopyFrom(const SubscribeCurrentSettingsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const StartVideoRequest& from) { + void MergeFrom(const SubscribeCurrentSettingsRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -2885,11 +2851,11 @@ class StartVideoRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StartVideoRequest"; + return "mavsdk.rpc.camera.SubscribeCurrentSettingsRequest"; } protected: - explicit StartVideoRequest(::google::protobuf::Arena* arena); - StartVideoRequest(::google::protobuf::Arena* arena, const StartVideoRequest& from); + explicit SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena); + SubscribeCurrentSettingsRequest(::google::protobuf::Arena* arena, const SubscribeCurrentSettingsRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -2898,7 +2864,7 @@ class StartVideoRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCurrentSettingsRequest) private: class _Internal; @@ -2921,26 +2887,25 @@ class StartVideoRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class StartPhotoIntervalRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartPhotoIntervalRequest) */ { +class SubscribeCaptureInfoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) */ { public: - inline StartPhotoIntervalRequest() : StartPhotoIntervalRequest(nullptr) {} - ~StartPhotoIntervalRequest() override; + inline SubscribeCaptureInfoRequest() : SubscribeCaptureInfoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR StartPhotoIntervalRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeCaptureInfoRequest(::google::protobuf::internal::ConstantInitialized); - inline StartPhotoIntervalRequest(const StartPhotoIntervalRequest& from) - : StartPhotoIntervalRequest(nullptr, from) {} - StartPhotoIntervalRequest(StartPhotoIntervalRequest&& from) noexcept - : StartPhotoIntervalRequest() { + inline SubscribeCaptureInfoRequest(const SubscribeCaptureInfoRequest& from) + : SubscribeCaptureInfoRequest(nullptr, from) {} + SubscribeCaptureInfoRequest(SubscribeCaptureInfoRequest&& from) noexcept + : SubscribeCaptureInfoRequest() { *this = ::std::move(from); } - inline StartPhotoIntervalRequest& operator=(const StartPhotoIntervalRequest& from) { + inline SubscribeCaptureInfoRequest& operator=(const SubscribeCaptureInfoRequest& from) { CopyFrom(from); return *this; } - inline StartPhotoIntervalRequest& operator=(StartPhotoIntervalRequest&& from) noexcept { + inline SubscribeCaptureInfoRequest& operator=(SubscribeCaptureInfoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2972,20 +2937,20 @@ class StartPhotoIntervalRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StartPhotoIntervalRequest& default_instance() { + static const SubscribeCaptureInfoRequest& default_instance() { return *internal_default_instance(); } - static inline const StartPhotoIntervalRequest* internal_default_instance() { - return reinterpret_cast( - &_StartPhotoIntervalRequest_default_instance_); + static inline const SubscribeCaptureInfoRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeCaptureInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 26; - friend void swap(StartPhotoIntervalRequest& a, StartPhotoIntervalRequest& b) { + friend void swap(SubscribeCaptureInfoRequest& a, SubscribeCaptureInfoRequest& b) { a.Swap(&b); } - inline void Swap(StartPhotoIntervalRequest* other) { + inline void Swap(SubscribeCaptureInfoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2998,7 +2963,7 @@ class StartPhotoIntervalRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StartPhotoIntervalRequest* other) { + void UnsafeArenaSwap(SubscribeCaptureInfoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3006,74 +2971,39 @@ class StartPhotoIntervalRequest final : // implements Message ---------------------------------------------- - StartPhotoIntervalRequest* 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::Message::CopyFrom; - void CopyFrom(const StartPhotoIntervalRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StartPhotoIntervalRequest& from) { - StartPhotoIntervalRequest::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeCaptureInfoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeCaptureInfoRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::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(StartPhotoIntervalRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.StartPhotoIntervalRequest"; + return "mavsdk.rpc.camera.SubscribeCaptureInfoRequest"; } protected: - explicit StartPhotoIntervalRequest(::google::protobuf::Arena* arena); - StartPhotoIntervalRequest(::google::protobuf::Arena* arena, const StartPhotoIntervalRequest& from); + explicit SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena); + SubscribeCaptureInfoRequest(::google::protobuf::Arena* arena, const SubscribeCaptureInfoRequest& 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 { - kIntervalSFieldNumber = 1, - }; - // float interval_s = 1; - void clear_interval_s() ; - float interval_s() const; - void set_interval_s(float value); - - private: - float _internal_interval_s() const; - void _internal_set_interval_s(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartPhotoIntervalRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SubscribeCaptureInfoRequest) 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 @@ -3088,34 +3018,31 @@ class StartPhotoIntervalRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float interval_s_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class SetModeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.SetModeRequest) */ { +class StopVideoStreamingRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoStreamingRequest) */ { public: - inline SetModeRequest() : SetModeRequest(nullptr) {} - ~SetModeRequest() override; + inline StopVideoStreamingRequest() : StopVideoStreamingRequest(nullptr) {} + ~StopVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR SetModeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline SetModeRequest(const SetModeRequest& from) - : SetModeRequest(nullptr, from) {} - SetModeRequest(SetModeRequest&& from) noexcept - : SetModeRequest() { + inline StopVideoStreamingRequest(const StopVideoStreamingRequest& from) + : StopVideoStreamingRequest(nullptr, from) {} + StopVideoStreamingRequest(StopVideoStreamingRequest&& from) noexcept + : StopVideoStreamingRequest() { *this = ::std::move(from); } - inline SetModeRequest& operator=(const SetModeRequest& from) { + inline StopVideoStreamingRequest& operator=(const StopVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline SetModeRequest& operator=(SetModeRequest&& from) noexcept { + inline StopVideoStreamingRequest& operator=(StopVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3147,20 +3074,20 @@ class SetModeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetModeRequest& default_instance() { + static const StopVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const SetModeRequest* internal_default_instance() { - return reinterpret_cast( - &_SetModeRequest_default_instance_); + static inline const StopVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_StopVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 14; - friend void swap(SetModeRequest& a, SetModeRequest& b) { + friend void swap(StopVideoStreamingRequest& a, StopVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(SetModeRequest* other) { + inline void Swap(StopVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3173,7 +3100,7 @@ class SetModeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetModeRequest* other) { + void UnsafeArenaSwap(StopVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3181,14 +3108,14 @@ class SetModeRequest final : // implements Message ---------------------------------------------- - SetModeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetModeRequest& from); + void CopyFrom(const StopVideoStreamingRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetModeRequest& from) { - SetModeRequest::MergeImpl(*this, from); + void MergeFrom( const StopVideoStreamingRequest& from) { + StopVideoStreamingRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3206,16 +3133,16 @@ class SetModeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetModeRequest* other); + void InternalSwap(StopVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SetModeRequest"; + return "mavsdk.rpc.camera.StopVideoStreamingRequest"; } protected: - explicit SetModeRequest(::google::protobuf::Arena* arena); - SetModeRequest(::google::protobuf::Arena* arena, const SetModeRequest& from); + explicit StopVideoStreamingRequest(::google::protobuf::Arena* arena); + StopVideoStreamingRequest(::google::protobuf::Arena* arena, const StopVideoStreamingRequest& from); public: static const ClassData _class_data_; @@ -3228,19 +3155,19 @@ class SetModeRequest final : // accessors ------------------------------------------------------- enum : int { - kModeFieldNumber = 1, + kStreamIdFieldNumber = 1, }; - // .mavsdk.rpc.camera.Mode mode = 1; - void clear_mode() ; - ::mavsdk::rpc::camera::Mode mode() const; - void set_mode(::mavsdk::rpc::camera::Mode value); + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); private: - ::mavsdk::rpc::camera::Mode _internal_mode() const; - void _internal_set_mode(::mavsdk::rpc::camera::Mode value); + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.SetModeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopVideoStreamingRequest) private: class _Internal; @@ -3263,7 +3190,7 @@ class SetModeRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int mode_; + ::int32_t stream_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -3271,26 +3198,25 @@ 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 StopVideoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopVideoRequest) */ { public: - inline SelectCameraRequest() : SelectCameraRequest(nullptr) {} - ~SelectCameraRequest() override; + inline StopVideoRequest() : StopVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SelectCameraRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline SelectCameraRequest(const SelectCameraRequest& from) - : SelectCameraRequest(nullptr, from) {} - SelectCameraRequest(SelectCameraRequest&& from) noexcept - : SelectCameraRequest() { + inline StopVideoRequest(const StopVideoRequest& from) + : StopVideoRequest(nullptr, from) {} + StopVideoRequest(StopVideoRequest&& from) noexcept + : StopVideoRequest() { *this = ::std::move(from); } - inline SelectCameraRequest& operator=(const SelectCameraRequest& from) { + inline StopVideoRequest& operator=(const StopVideoRequest& from) { CopyFrom(from); return *this; } - inline SelectCameraRequest& operator=(SelectCameraRequest&& from) noexcept { + inline StopVideoRequest& operator=(StopVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3322,20 +3248,20 @@ class SelectCameraRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SelectCameraRequest& default_instance() { + static const StopVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const SelectCameraRequest* internal_default_instance() { - return reinterpret_cast( - &_SelectCameraRequest_default_instance_); + static inline const StopVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_StopVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 41; + 10; - friend void swap(SelectCameraRequest& a, SelectCameraRequest& b) { + friend void swap(StopVideoRequest& a, StopVideoRequest& b) { a.Swap(&b); } - inline void Swap(SelectCameraRequest* other) { + inline void Swap(StopVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3348,7 +3274,7 @@ class SelectCameraRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SelectCameraRequest* other) { + void UnsafeArenaSwap(StopVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3356,74 +3282,39 @@ class SelectCameraRequest final : // implements Message ---------------------------------------------- - SelectCameraRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopVideoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SelectCameraRequest& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SelectCameraRequest& from) { - SelectCameraRequest::MergeImpl(*this, from); + 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); } - 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(SelectCameraRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.SelectCameraRequest"; + return "mavsdk.rpc.camera.StopVideoRequest"; } protected: - explicit SelectCameraRequest(::google::protobuf::Arena* arena); - SelectCameraRequest(::google::protobuf::Arena* arena, const SelectCameraRequest& from); + explicit StopVideoRequest(::google::protobuf::Arena* arena); + 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.SelectCameraRequest) + // @@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 @@ -3438,33 +3329,30 @@ class SelectCameraRequest 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 ResetSettingsRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.ResetSettingsRequest) */ { +class StopPhotoIntervalRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StopPhotoIntervalRequest) */ { public: - inline ResetSettingsRequest() : ResetSettingsRequest(nullptr) {} + inline StopPhotoIntervalRequest() : StopPhotoIntervalRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR ResetSettingsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StopPhotoIntervalRequest(::google::protobuf::internal::ConstantInitialized); - inline ResetSettingsRequest(const ResetSettingsRequest& from) - : ResetSettingsRequest(nullptr, from) {} - ResetSettingsRequest(ResetSettingsRequest&& from) noexcept - : ResetSettingsRequest() { + inline StopPhotoIntervalRequest(const StopPhotoIntervalRequest& from) + : StopPhotoIntervalRequest(nullptr, from) {} + StopPhotoIntervalRequest(StopPhotoIntervalRequest&& from) noexcept + : StopPhotoIntervalRequest() { *this = ::std::move(from); } - inline ResetSettingsRequest& operator=(const ResetSettingsRequest& from) { + inline StopPhotoIntervalRequest& operator=(const StopPhotoIntervalRequest& from) { CopyFrom(from); return *this; } - inline ResetSettingsRequest& operator=(ResetSettingsRequest&& from) noexcept { + inline StopPhotoIntervalRequest& operator=(StopPhotoIntervalRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3496,20 +3384,20 @@ class ResetSettingsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ResetSettingsRequest& default_instance() { + static const StopPhotoIntervalRequest& default_instance() { return *internal_default_instance(); } - static inline const ResetSettingsRequest* internal_default_instance() { - return reinterpret_cast( - &_ResetSettingsRequest_default_instance_); + static inline const StopPhotoIntervalRequest* internal_default_instance() { + return reinterpret_cast( + &_StopPhotoIntervalRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 6; - friend void swap(ResetSettingsRequest& a, ResetSettingsRequest& b) { + friend void swap(StopPhotoIntervalRequest& a, StopPhotoIntervalRequest& b) { a.Swap(&b); } - inline void Swap(ResetSettingsRequest* other) { + inline void Swap(StopPhotoIntervalRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3522,7 +3410,7 @@ class ResetSettingsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ResetSettingsRequest* other) { + void UnsafeArenaSwap(StopPhotoIntervalRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3530,15 +3418,15 @@ class ResetSettingsRequest final : // implements Message ---------------------------------------------- - ResetSettingsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StopPhotoIntervalRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ResetSettingsRequest& from) { + inline void CopyFrom(const StopPhotoIntervalRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ResetSettingsRequest& from) { + void MergeFrom(const StopPhotoIntervalRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -3546,11 +3434,11 @@ class ResetSettingsRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.ResetSettingsRequest"; + return "mavsdk.rpc.camera.StopPhotoIntervalRequest"; } protected: - explicit ResetSettingsRequest(::google::protobuf::Arena* arena); - ResetSettingsRequest(::google::protobuf::Arena* arena, const ResetSettingsRequest& from); + explicit StopPhotoIntervalRequest(::google::protobuf::Arena* arena); + StopPhotoIntervalRequest(::google::protobuf::Arena* arena, const StopPhotoIntervalRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -3559,7 +3447,7 @@ class ResetSettingsRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.ResetSettingsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StopPhotoIntervalRequest) private: class _Internal; @@ -3582,26 +3470,26 @@ class ResetSettingsRequest final : friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class Quaternion final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Quaternion) */ { +class Status final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Status) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline Status() : Status(nullptr) {} + ~Status() override; template - explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Status(::google::protobuf::internal::ConstantInitialized); - inline Quaternion(const Quaternion& from) - : Quaternion(nullptr, from) {} - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + inline Status(const Status& from) + : Status(nullptr, from) {} + Status(Status&& from) noexcept + : Status() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline Status& operator=(const Status& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline Status& operator=(Status&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3633,20 +3521,20 @@ class Quaternion final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const Status& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const Status* internal_default_instance() { + return reinterpret_cast( + &_Status_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 73; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(Status& a, Status& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(Status* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3659,7 +3547,7 @@ class Quaternion final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(Status* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3667,14 +3555,14 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Status* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const Status& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const Status& from) { + Status::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3692,16 +3580,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(Status* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.Quaternion"; + return "mavsdk.rpc.camera.Status"; } protected: - explicit Quaternion(::google::protobuf::Arena* arena); - Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); + explicit Status(::google::protobuf::Arena* arena); + Status(::google::protobuf::Arena* arena, const Status& from); public: static const ClassData _class_data_; @@ -3711,62 +3599,180 @@ class Quaternion final : // nested types ---------------------------------------------------- + using StorageStatus = Status_StorageStatus; + static constexpr StorageStatus STORAGE_STATUS_NOT_AVAILABLE = Status_StorageStatus_STORAGE_STATUS_NOT_AVAILABLE; + static constexpr StorageStatus STORAGE_STATUS_UNFORMATTED = Status_StorageStatus_STORAGE_STATUS_UNFORMATTED; + static constexpr StorageStatus STORAGE_STATUS_FORMATTED = Status_StorageStatus_STORAGE_STATUS_FORMATTED; + static constexpr StorageStatus STORAGE_STATUS_NOT_SUPPORTED = Status_StorageStatus_STORAGE_STATUS_NOT_SUPPORTED; + static inline bool StorageStatus_IsValid(int value) { + return Status_StorageStatus_IsValid(value); + } + static constexpr StorageStatus StorageStatus_MIN = Status_StorageStatus_StorageStatus_MIN; + static constexpr StorageStatus StorageStatus_MAX = Status_StorageStatus_StorageStatus_MAX; + static constexpr int StorageStatus_ARRAYSIZE = Status_StorageStatus_StorageStatus_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* StorageStatus_descriptor() { + return Status_StorageStatus_descriptor(); + } + template + static inline const std::string& StorageStatus_Name(T value) { + return Status_StorageStatus_Name(value); + } + static inline bool StorageStatus_Parse(absl::string_view name, StorageStatus* value) { + return Status_StorageStatus_Parse(name, value); + } + + using StorageType = Status_StorageType; + static constexpr StorageType STORAGE_TYPE_UNKNOWN = Status_StorageType_STORAGE_TYPE_UNKNOWN; + static constexpr StorageType STORAGE_TYPE_USB_STICK = Status_StorageType_STORAGE_TYPE_USB_STICK; + static constexpr StorageType STORAGE_TYPE_SD = Status_StorageType_STORAGE_TYPE_SD; + static constexpr StorageType STORAGE_TYPE_MICROSD = Status_StorageType_STORAGE_TYPE_MICROSD; + static constexpr StorageType STORAGE_TYPE_HD = Status_StorageType_STORAGE_TYPE_HD; + static constexpr StorageType STORAGE_TYPE_OTHER = Status_StorageType_STORAGE_TYPE_OTHER; + static inline bool StorageType_IsValid(int value) { + return Status_StorageType_IsValid(value); + } + static constexpr StorageType StorageType_MIN = Status_StorageType_StorageType_MIN; + static constexpr StorageType StorageType_MAX = Status_StorageType_StorageType_MAX; + static constexpr int StorageType_ARRAYSIZE = Status_StorageType_StorageType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* StorageType_descriptor() { + return Status_StorageType_descriptor(); + } + template + static inline const std::string& StorageType_Name(T value) { + return Status_StorageType_Name(value); + } + static inline bool StorageType_Parse(absl::string_view name, StorageType* value) { + return Status_StorageType_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, + kMediaFolderNameFieldNumber = 7, + kVideoOnFieldNumber = 1, + kPhotoIntervalOnFieldNumber = 2, + kUsedStorageMibFieldNumber = 3, + kAvailableStorageMibFieldNumber = 4, + kTotalStorageMibFieldNumber = 5, + kRecordingTimeSFieldNumber = 6, + kStorageStatusFieldNumber = 8, + kStorageIdFieldNumber = 9, + kStorageTypeFieldNumber = 10, }; - // float w = 1; - void clear_w() ; - float w() const; - void set_w(float value); + // string media_folder_name = 7; + void clear_media_folder_name() ; + const std::string& media_folder_name() const; + template + void set_media_folder_name(Arg_&& arg, Args_... args); + std::string* mutable_media_folder_name(); + PROTOBUF_NODISCARD std::string* release_media_folder_name(); + void set_allocated_media_folder_name(std::string* value); private: - float _internal_w() const; - void _internal_set_w(float value); + const std::string& _internal_media_folder_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_media_folder_name( + const std::string& value); + std::string* _internal_mutable_media_folder_name(); public: - // float x = 2; - void clear_x() ; - float x() const; - void set_x(float value); + // bool video_on = 1; + void clear_video_on() ; + bool video_on() const; + void set_video_on(bool value); private: - float _internal_x() const; - void _internal_set_x(float value); - + bool _internal_video_on() const; + void _internal_set_video_on(bool value); + public: - // float y = 3; - void clear_y() ; - float y() const; - void set_y(float value); + // bool photo_interval_on = 2; + void clear_photo_interval_on() ; + bool photo_interval_on() const; + void set_photo_interval_on(bool value); private: - float _internal_y() const; - void _internal_set_y(float value); + bool _internal_photo_interval_on() const; + void _internal_set_photo_interval_on(bool value); public: - // float z = 4; - void clear_z() ; - float z() const; - void set_z(float value); + // float used_storage_mib = 3; + void clear_used_storage_mib() ; + float used_storage_mib() const; + void set_used_storage_mib(float value); private: - float _internal_z() const; - void _internal_set_z(float value); + float _internal_used_storage_mib() const; + void _internal_set_used_storage_mib(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Quaternion) + // float available_storage_mib = 4; + void clear_available_storage_mib() ; + float available_storage_mib() const; + void set_available_storage_mib(float value); + + private: + float _internal_available_storage_mib() const; + void _internal_set_available_storage_mib(float value); + + public: + // float total_storage_mib = 5; + void clear_total_storage_mib() ; + float total_storage_mib() const; + void set_total_storage_mib(float value); + + private: + float _internal_total_storage_mib() const; + void _internal_set_total_storage_mib(float value); + + public: + // float recording_time_s = 6; + void clear_recording_time_s() ; + float recording_time_s() const; + void set_recording_time_s(float value); + + private: + float _internal_recording_time_s() const; + void _internal_set_recording_time_s(float value); + + public: + // .mavsdk.rpc.camera.Status.StorageStatus storage_status = 8; + void clear_storage_status() ; + ::mavsdk::rpc::camera::Status_StorageStatus storage_status() const; + void set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); + + private: + ::mavsdk::rpc::camera::Status_StorageStatus _internal_storage_status() const; + void _internal_set_storage_status(::mavsdk::rpc::camera::Status_StorageStatus value); + + public: + // uint32 storage_id = 9; + void clear_storage_id() ; + ::uint32_t storage_id() const; + void set_storage_id(::uint32_t value); + + private: + ::uint32_t _internal_storage_id() const; + void _internal_set_storage_id(::uint32_t value); + + public: + // .mavsdk.rpc.camera.Status.StorageType storage_type = 10; + void clear_storage_type() ; + ::mavsdk::rpc::camera::Status_StorageType storage_type() const; + void set_storage_type(::mavsdk::rpc::camera::Status_StorageType value); + + private: + ::mavsdk::rpc::camera::Status_StorageType _internal_storage_type() const; + void _internal_set_storage_type(::mavsdk::rpc::camera::Status_StorageType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Status) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, - 0, 2> + 4, 10, 0, + 58, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -3782,10 +3788,16 @@ 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_; + ::google::protobuf::internal::ArenaStringPtr media_folder_name_; + bool video_on_; + bool photo_interval_on_; + float used_storage_mib_; + float available_storage_mib_; + float total_storage_mib_; + float recording_time_s_; + int storage_status_; + ::uint32_t storage_id_; + int storage_type_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -3793,25 +3805,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 StartVideoStreamingRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoStreamingRequest) */ { public: - inline PrepareRequest() : PrepareRequest(nullptr) {} + inline StartVideoStreamingRequest() : StartVideoStreamingRequest(nullptr) {} + ~StartVideoStreamingRequest() override; template - explicit PROTOBUF_CONSTEXPR PrepareRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoStreamingRequest(::google::protobuf::internal::ConstantInitialized); - inline PrepareRequest(const PrepareRequest& from) - : PrepareRequest(nullptr, from) {} - PrepareRequest(PrepareRequest&& from) noexcept - : PrepareRequest() { + inline StartVideoStreamingRequest(const StartVideoStreamingRequest& from) + : StartVideoStreamingRequest(nullptr, from) {} + StartVideoStreamingRequest(StartVideoStreamingRequest&& from) noexcept + : StartVideoStreamingRequest() { *this = ::std::move(from); } - inline PrepareRequest& operator=(const PrepareRequest& from) { + inline StartVideoStreamingRequest& operator=(const StartVideoStreamingRequest& from) { CopyFrom(from); return *this; } - inline PrepareRequest& operator=(PrepareRequest&& from) noexcept { + inline StartVideoStreamingRequest& operator=(StartVideoStreamingRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3843,20 +3856,20 @@ class PrepareRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PrepareRequest& default_instance() { + static const StartVideoStreamingRequest& default_instance() { return *internal_default_instance(); } - static inline const PrepareRequest* internal_default_instance() { - return reinterpret_cast( - &_PrepareRequest_default_instance_); + static inline const StartVideoStreamingRequest* internal_default_instance() { + return reinterpret_cast( + &_StartVideoStreamingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 0; + 12; - friend void swap(PrepareRequest& a, PrepareRequest& b) { + friend void swap(StartVideoStreamingRequest& a, StartVideoStreamingRequest& b) { a.Swap(&b); } - inline void Swap(PrepareRequest* other) { + inline void Swap(StartVideoStreamingRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3869,7 +3882,7 @@ class PrepareRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PrepareRequest* other) { + void UnsafeArenaSwap(StartVideoStreamingRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3877,39 +3890,74 @@ 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); + StartVideoStreamingRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const PrepareRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StartVideoStreamingRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StartVideoStreamingRequest& from) { + StartVideoStreamingRequest::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(StartVideoStreamingRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.PrepareRequest"; + return "mavsdk.rpc.camera.StartVideoStreamingRequest"; } protected: - explicit PrepareRequest(::google::protobuf::Arena* arena); - PrepareRequest(::google::protobuf::Arena* arena, const PrepareRequest& from); + explicit StartVideoStreamingRequest(::google::protobuf::Arena* arena); + StartVideoStreamingRequest(::google::protobuf::Arena* arena, const StartVideoStreamingRequest& 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.PrepareRequest) + enum : int { + kStreamIdFieldNumber = 1, + }; + // int32 stream_id = 1; + void clear_stream_id() ; + ::int32_t stream_id() const; + void set_stream_id(::int32_t value); + + private: + ::int32_t _internal_stream_id() const; + void _internal_set_stream_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoStreamingRequest) private: class _Internal; + 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 @@ -3924,31 +3972,33 @@ class PrepareRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t stream_id_; + 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) */ { +class StartVideoRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartVideoRequest) */ { public: - inline Position() : Position(nullptr) {} - ~Position() override; + inline StartVideoRequest() : StartVideoRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartVideoRequest(::google::protobuf::internal::ConstantInitialized); - inline Position(const Position& from) - : Position(nullptr, from) {} - Position(Position&& from) noexcept - : Position() { + inline StartVideoRequest(const StartVideoRequest& from) + : StartVideoRequest(nullptr, from) {} + StartVideoRequest(StartVideoRequest&& from) noexcept + : StartVideoRequest() { *this = ::std::move(from); } - inline Position& operator=(const Position& from) { + inline StartVideoRequest& operator=(const StartVideoRequest& from) { CopyFrom(from); return *this; } - inline Position& operator=(Position&& from) noexcept { + inline StartVideoRequest& operator=(StartVideoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3980,20 +4030,20 @@ class Position final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Position& default_instance() { + static const StartVideoRequest& default_instance() { return *internal_default_instance(); } - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const StartVideoRequest* internal_default_instance() { + return reinterpret_cast( + &_StartVideoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 45; + 8; - friend void swap(Position& a, Position& b) { + friend void swap(StartVideoRequest& a, StartVideoRequest& b) { a.Swap(&b); } - inline void Swap(Position* other) { + inline void Swap(StartVideoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4006,7 +4056,7 @@ class Position final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Position* other) { + void UnsafeArenaSwap(StartVideoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4014,107 +4064,39 @@ class Position final : // implements Message ---------------------------------------------- - Position* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Position& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Position& from) { - Position::MergeImpl(*this, from); + 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); } - 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(Position* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.camera.Position"; + return "mavsdk.rpc.camera.StartVideoRequest"; } protected: - explicit Position(::google::protobuf::Arena* arena); - Position(::google::protobuf::Arena* arena, const Position& from); + explicit StartVideoRequest(::google::protobuf::Arena* arena); + 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 { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, - kRelativeAltitudeMFieldNumber = 4, - }; - // double latitude_deg = 1; - void clear_latitude_deg() ; - double latitude_deg() const; - void set_latitude_deg(double value); - - private: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); - - public: - // double longitude_deg = 2; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); - - private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); - - public: - // float absolute_altitude_m = 3; - void clear_absolute_altitude_m() ; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); - - private: - float _internal_absolute_altitude_m() const; - void _internal_set_absolute_altitude_m(float value); - - public: - // float relative_altitude_m = 4; - void clear_relative_altitude_m() ; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); - - private: - float _internal_relative_altitude_m() const; - void _internal_set_relative_altitude_m(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.Position) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera.StartVideoRequest) 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 @@ -4129,37 +4111,31 @@ class Position final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - 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 }; - union { Impl_ _impl_; }; friend struct ::TableStruct_camera_2fcamera_2eproto; };// ------------------------------------------------------------------- -class Option final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.Option) */ { +class StartPhotoIntervalRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.camera.StartPhotoIntervalRequest) */ { public: - inline Option() : Option(nullptr) {} - ~Option() override; + inline StartPhotoIntervalRequest() : StartPhotoIntervalRequest(nullptr) {} + ~StartPhotoIntervalRequest() override; template - explicit PROTOBUF_CONSTEXPR Option(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StartPhotoIntervalRequest(::google::protobuf::internal::ConstantInitialized); - inline Option(const Option& from) - : Option(nullptr, from) {} - Option(Option&& from) noexcept - : Option() { + inline StartPhotoIntervalRequest(const StartPhotoIntervalRequest& from) + : StartPhotoIntervalRequest(nullptr, from) {} + StartPhotoIntervalRequest(StartPhotoIntervalRequest&& from) noexcept + : StartPhotoIntervalRequest() { *this = ::std::move(from); } - inline Option& operator=(const Option& from) { + inline StartPhotoIntervalRequest& operator=(const StartPhotoIntervalRequest& from) { CopyFrom(from); return *this; } - inline Option& operator=(Option&& from) noexcept { + inline StartPhotoIntervalRequest& operator=(StartPhotoIntervalRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -4191,20 +4167,20 @@ class Option final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Option& default_instance() { + static const StartPhotoIntervalRequest& default_instance() { return *internal_default_instance(); } - static inline const Option* internal_default_instance() { - return reinterpret_cast( - &_Option_default_instance_); + static inline const StartPhotoIntervalRequest* internal_default_instance() { + return reinterpret_cast( + &_StartPhotoIntervalRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 4; - friend void swap(Option& a, Option& b) { + friend void swap(StartPhotoIntervalRequest& a, StartPhotoIntervalRequest& b) { a.Swap(&b); } - inline void Swap(Option* other) { + inline void Swap(StartPhotoIntervalRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -4217,7 +4193,7 @@ class Option final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Option* other) { + void UnsafeArenaSwap(StartPhotoIntervalRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -4225,14 +4201,14 @@ class Option final : // implements Message ---------------------------------------------- - Option* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage