From e64553aab4fb717597b1d56bb88dee990eac18a4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 26 Jul 2024 02:06:18 +1200 Subject: [PATCH] telemetry: remove camera attitude This is better covered by the gimbal plugin. --- .../gimbal_full_control.cpp | 16 +- proto | 2 +- src/integration_tests/telemetry_async.cpp | 40 - .../include/plugins/telemetry/telemetry.h | 77 +- .../plugins/telemetry/mocks/telemetry_mock.h | 11 - src/mavsdk/plugins/telemetry/telemetry.cpp | 42 - .../plugins/telemetry/telemetry_impl.cpp | 147 - src/mavsdk/plugins/telemetry/telemetry_impl.h | 18 - .../generated/telemetry/telemetry.grpc.pb.cc | 298 +- .../generated/telemetry/telemetry.grpc.pb.h | 1315 +- .../src/generated/telemetry/telemetry.pb.cc | 7634 +++++------ .../src/generated/telemetry/telemetry.pb.h | 11230 +++++++--------- .../telemetry/telemetry_service_impl.h | 112 - .../test/telemetry_service_impl_test.cpp | 185 - 14 files changed, 8276 insertions(+), 12851 deletions(-) diff --git a/examples/gimbal_full_control/gimbal_full_control.cpp b/examples/gimbal_full_control/gimbal_full_control.cpp index e16dec8435..6a7cbbfc4b 100644 --- a/examples/gimbal_full_control/gimbal_full_control.cpp +++ b/examples/gimbal_full_control/gimbal_full_control.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #include #include #include @@ -50,20 +49,11 @@ int main(int argc, char** argv) } // Instantiate plugins. - auto telemetry = Telemetry{system.value()}; auto gimbal = Gimbal{system.value()}; - // We want to listen to the camera/gimbal angle of the drone at 5 Hz. - const Telemetry::Result set_rate_result = telemetry.set_rate_camera_attitude(5.0); - if (set_rate_result != Telemetry::Result::Success) { - std::cerr << "Setting rate failed:" << set_rate_result << '\n'; - return 1; - } - - // Set up callback to monitor camera/gimbal angle - telemetry.subscribe_camera_attitude_euler([](Telemetry::EulerAngle angle) { - std::cout << "Gimbal angle pitch: " << angle.pitch_deg << " deg, yaw: " << angle.yaw_deg - << " deg, roll: " << angle.roll_deg << " deg\n"; + gimbal.subscribe_attitude([](Gimbal::Attitude attitude) { + std::cout << "Gimbal angle pitch: " << attitude.euler_angle_forward.pitch_deg + << " deg, yaw: " << attitude.euler_angle_forward.yaw_deg << " deg\n"; }); std::cout << "Start controlling gimbal...\n"; diff --git a/proto b/proto index 48f658d00b..5524f43c33 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 48f658d00bfb6d3dc4884062b7371ddfe1a1765a +Subproject commit 5524f43c336552dfcfeb645174c96741ae986241 diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 0cfe15941e..e78c188158 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -5,8 +5,6 @@ #include "mavsdk.h" #include "plugins/telemetry/telemetry.h" -#define CAMERA_AVAILABLE 0 // Set to 1 if camera is available and should be tested. - using namespace mavsdk; static void receive_result(Telemetry::Result result); @@ -19,10 +17,6 @@ static void print_euler_angle(Telemetry::EulerAngle euler_angle); static void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body); static void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics); static void print_ground_truth(const Telemetry::GroundTruth& ground_truth); -#if CAMERA_AVAILABLE == 1 -static void print_camera_quaternion(Telemetry::Quaternion quaternion); -static void print_camera_euler_angle(Telemetry::EulerAngle euler_angle); -#endif static void print_velocity_ned(Telemetry::VelocityNed velocity_ned); static void print_imu(Telemetry::Imu imu); static void print_gps_info(Telemetry::GpsInfo gps_info); @@ -44,10 +38,6 @@ static bool _received_euler_angle = false; static bool _received_angular_velocity_body = false; static bool _received_fixedwing_metrics = false; static bool _received_ground_truth = false; -#if CAMERA_AVAILABLE == 1 -static bool _received_camera_quaternion = false; -static bool _received_camera_euler_angle = false; -#endif static bool _received_velocity = false; static bool _received_imu = false; static bool _received_gps_info = false; @@ -153,14 +143,6 @@ TEST(SitlTest, PX4TelemetryAsync) telemetry->subscribe_ground_truth( [](Telemetry::GroundTruth ground_truth) { print_ground_truth(ground_truth); }); -#if CAMERA_AVAILABLE == 1 - telemetry->subscribe_camera_attitude_quaternion( - [](Telemetry::Quaternion quaternion) { print_camera_quaternion(quaternion); }); - - telemetry->subscribe_camera_attitude_euler( - [](Telemetry::EulerAngle euler_angle) { print_camera_euler_angle(euler_angle); }); -#endif - telemetry->subscribe_velocity_ned( [](Telemetry::VelocityNed velocity_ned) { print_velocity_ned(velocity_ned); }); @@ -206,10 +188,6 @@ TEST(SitlTest, PX4TelemetryAsync) EXPECT_TRUE(_received_fixedwing_metrics); EXPECT_TRUE(_received_ground_truth); EXPECT_TRUE(_received_euler_angle); -#if CAMERA_AVAILABLE == 1 - EXPECT_TRUE(_received_camera_quaternion); - EXPECT_TRUE(_received_camera_euler_angle); -#endif EXPECT_TRUE(_received_velocity); EXPECT_TRUE(_received_imu); EXPECT_TRUE(_received_gps_info); @@ -297,24 +275,6 @@ void print_ground_truth(const Telemetry::GroundTruth& ground_truth) _received_ground_truth = true; } -#if CAMERA_AVAILABLE == 1 -void print_camera_quaternion(Telemetry::Quaternion quaternion) -{ - std::cout << "Camera Quaternion: [ " << quaternion.w << ", " << quaternion.x << ", " - << quaternion.y << ", " << quaternion.z << " ]" << '\n'; - - _received_camera_quaternion = true; -} - -void print_camera_euler_angle(Telemetry::EulerAngle euler_angle) -{ - std::cout << "Camera Euler angle: [ " << euler_angle.roll_deg << ", " << euler_angle.pitch_deg - << ", " << euler_angle.yaw_deg << " ] deg" << '\n'; - - _received_camera_euler_angle = true; -} -#endif - void print_velocity_ned(Telemetry::VelocityNed velocity_ned) { std::cout << "Ground speed NED: [ " << velocity_ned.north_m_s << ", " << velocity_ned.east_m_s diff --git a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h index 6c11043710..07b1addabe 100644 --- a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -1266,62 +1266,6 @@ class Telemetry : public PluginBase { */ AngularVelocityBody attitude_angular_velocity_body() const; - /** - * @brief Callback type for subscribe_camera_attitude_quaternion. - */ - using CameraAttitudeQuaternionCallback = std::function; - - /** - * @brief Handle type for subscribe_camera_attitude_quaternion. - */ - using CameraAttitudeQuaternionHandle = Handle; - - /** - * @brief Subscribe to 'camera attitude' updates (quaternion). - */ - CameraAttitudeQuaternionHandle - subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback& callback); - - /** - * @brief Unsubscribe from subscribe_camera_attitude_quaternion - */ - void unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle); - - /** - * @brief Poll for 'Quaternion' (blocking). - * - * @return One Quaternion update. - */ - Quaternion camera_attitude_quaternion() const; - - /** - * @brief Callback type for subscribe_camera_attitude_euler. - */ - using CameraAttitudeEulerCallback = std::function; - - /** - * @brief Handle type for subscribe_camera_attitude_euler. - */ - using CameraAttitudeEulerHandle = Handle; - - /** - * @brief Subscribe to 'camera attitude' updates (Euler). - */ - CameraAttitudeEulerHandle - subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback& callback); - - /** - * @brief Unsubscribe from subscribe_camera_attitude_euler - */ - void unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle); - - /** - * @brief Poll for 'EulerAngle' (blocking). - * - * @return One EulerAngle update. - */ - EulerAngle camera_attitude_euler() const; - /** * @brief Callback type for subscribe_velocity_ned. */ @@ -2064,30 +2008,15 @@ class Telemetry : public PluginBase { /** * @brief Set rate of camera attitude updates. - * - * This function is non-blocking. See 'set_rate_camera_attitude' for the blocking counterpart. - */ - void set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback); - - /** - * @brief Set rate of camera attitude updates. - * - * This function is blocking. See 'set_rate_camera_attitude_async' for the non-blocking - * counterpart. - * - * @return Result of request. - */ - Result set_rate_camera_attitude(double rate_hz) const; - - /** - * @brief Set rate to 'ground speed' updates (NED). + * Set rate to 'ground speed' updates (NED). * * This function is non-blocking. See 'set_rate_velocity_ned' for the blocking counterpart. */ void set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback); /** - * @brief Set rate to 'ground speed' updates (NED). + * @brief Set rate of camera attitude updates. + * Set rate to 'ground speed' updates (NED). * * This function is blocking. See 'set_rate_velocity_ned_async' for the non-blocking * counterpart. diff --git a/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h b/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h index 0c3bb9e09a..9192cfe03c 100644 --- a/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h +++ b/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h @@ -51,15 +51,6 @@ class MockTelemetry { subscribe_attitude_euler, Telemetry::AttitudeEulerHandle(Telemetry::AttitudeEulerCallback)){}; MOCK_CONST_METHOD1(unsubscribe_attitude_euler, void(Telemetry::AttitudeEulerHandle)){}; - MOCK_CONST_METHOD1( - subscribe_camera_attitude_quaternion, - Telemetry::AttitudeQuaternionHandle(Telemetry::AttitudeQuaternionCallback)){}; - MOCK_CONST_METHOD1( - unsubscribe_camera_attitude_quaternion, void(Telemetry::AttitudeQuaternionHandle)){}; - MOCK_CONST_METHOD1( - subscribe_camera_attitude_euler, - Telemetry::AttitudeEulerHandle(Telemetry::AttitudeEulerCallback)){}; - MOCK_CONST_METHOD1(unsubscribe_camera_attitude_euler, void(Telemetry::AttitudeEulerHandle)){}; MOCK_CONST_METHOD1( subscribe_velocity_ned, Telemetry::VelocityNedHandle(Telemetry::VelocityNedCallback)){}; MOCK_CONST_METHOD1(unsubscribe_velocity_ned, void(Telemetry::VelocityNedHandle)){}; @@ -125,7 +116,6 @@ class MockTelemetry { MOCK_METHOD1(set_rate_landed_state, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_attitude_quaternion, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_attitude_euler, Telemetry::Result(double)){}; - MOCK_METHOD1(set_rate_camera_attitude, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_velocity_ned, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_gps_info, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_raw_gps, Telemetry::Result(double)){}; @@ -153,7 +143,6 @@ class MockTelemetry { MOCK_CONST_METHOD2( set_rate_attitude_quaternion_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_attitude_euler_async, void(double, Telemetry::ResultCallback)){}; - MOCK_CONST_METHOD2(set_rate_camera_attitude_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_velocity_ned_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_gps_info_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_battery_async, void(double, Telemetry::ResultCallback)){}; diff --git a/src/mavsdk/plugins/telemetry/telemetry.cpp b/src/mavsdk/plugins/telemetry/telemetry.cpp index 3b2c42c819..f8b04f79f2 100644 --- a/src/mavsdk/plugins/telemetry/telemetry.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry.cpp @@ -188,38 +188,6 @@ Telemetry::AngularVelocityBody Telemetry::attitude_angular_velocity_body() const return _impl->attitude_angular_velocity_body(); } -Telemetry::CameraAttitudeQuaternionHandle -Telemetry::subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback& callback) -{ - return _impl->subscribe_camera_attitude_quaternion(callback); -} - -void Telemetry::unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle) -{ - _impl->unsubscribe_camera_attitude_quaternion(handle); -} - -Telemetry::Quaternion Telemetry::camera_attitude_quaternion() const -{ - return _impl->camera_attitude_quaternion(); -} - -Telemetry::CameraAttitudeEulerHandle -Telemetry::subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback& callback) -{ - return _impl->subscribe_camera_attitude_euler(callback); -} - -void Telemetry::unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle) -{ - _impl->unsubscribe_camera_attitude_euler(handle); -} - -Telemetry::EulerAngle Telemetry::camera_attitude_euler() const -{ - return _impl->camera_attitude_euler(); -} - Telemetry::VelocityNedHandle Telemetry::subscribe_velocity_ned(const VelocityNedCallback& callback) { return _impl->subscribe_velocity_ned(callback); @@ -642,16 +610,6 @@ Telemetry::Result Telemetry::set_rate_attitude_euler(double rate_hz) const return _impl->set_rate_attitude_euler(rate_hz); } -void Telemetry::set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback) -{ - _impl->set_rate_camera_attitude_async(rate_hz, callback); -} - -Telemetry::Result Telemetry::set_rate_camera_attitude(double rate_hz) const -{ - return _impl->set_rate_camera_attitude(rate_hz); -} - void Telemetry::set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback) { _impl->set_rate_velocity_ned_async(rate_hz, callback); diff --git a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp index dfd56d19e3..dae97d7169 100644 --- a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp @@ -83,18 +83,6 @@ void TelemetryImpl::init() [this](const mavlink_message_t& message) { process_attitude_quaternion(message); }, this); - _system_impl->register_mavlink_message_handler( - MAVLINK_MSG_ID_MOUNT_ORIENTATION, - [this](const mavlink_message_t& message) { process_mount_orientation(message); }, - this); - - _system_impl->register_mavlink_message_handler( - MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, - [this](const mavlink_message_t& message) { - process_gimbal_device_attitude_status(message); - }, - this); - _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_GPS_RAW_INT, [this](const mavlink_message_t& message) { process_gps_raw_int(message); }, @@ -302,12 +290,6 @@ Telemetry::Result TelemetryImpl::set_rate_attitude_euler(double rate_hz) _system_impl->set_msg_rate(MAVLINK_MSG_ID_ATTITUDE, rate_hz)); } -Telemetry::Result TelemetryImpl::set_rate_camera_attitude(double rate_hz) -{ - return telemetry_result_from_command_result( - _system_impl->set_msg_rate(MAVLINK_MSG_ID_MOUNT_ORIENTATION, rate_hz)); -} - Telemetry::Result TelemetryImpl::set_rate_velocity_ned(double rate_hz) { _velocity_ned_rate_hz = rate_hz; @@ -494,17 +476,6 @@ void TelemetryImpl::set_rate_attitude_euler_async( }); } -void TelemetryImpl::set_rate_camera_attitude_async( - double rate_hz, Telemetry::ResultCallback callback) -{ - _system_impl->set_msg_rate_async( - MAVLINK_MSG_ID_MOUNT_ORIENTATION, - rate_hz, - [callback](MavlinkCommandSender::Result command_result, float) { - command_result_callback(command_result, callback); - }); -} - void TelemetryImpl::set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback) { _velocity_ned_rate_hz = rate_hz; @@ -855,63 +826,6 @@ void TelemetryImpl::process_altitude(const mavlink_message_t& message) altitude(), [this](const auto& func) { _system_impl->call_user_callback(func); }); } -void TelemetryImpl::process_mount_orientation(const mavlink_message_t& message) -{ - // TODO: remove this one once we move all the way to gimbal v2 protocol - mavlink_mount_orientation_t mount_orientation; - mavlink_msg_mount_orientation_decode(&message, &mount_orientation); - - Telemetry::EulerAngle euler_angle; - euler_angle.roll_deg = mount_orientation.roll; - euler_angle.pitch_deg = mount_orientation.pitch; - euler_angle.yaw_deg = mount_orientation.yaw_absolute; - - set_camera_attitude_euler_angle(euler_angle); - - std::lock_guard lock(_subscription_mutex); - _camera_attitude_quaternion_subscriptions.queue( - camera_attitude_quaternion(), - [this](const auto& func) { _system_impl->call_user_callback(func); }); - - _camera_attitude_euler_angle_subscriptions.queue( - camera_attitude_euler(), - [this](const auto& func) { _system_impl->call_user_callback(func); }); -} - -void TelemetryImpl::process_gimbal_device_attitude_status(const mavlink_message_t& message) -{ - // We accept both MOUNT_ORIENTATION and GIMBAL_DEVICE_ATTITUDE_STATUS for now, - // in order to support both gimbal v1 and v2 protocols. - - mavlink_gimbal_device_attitude_status_t attitude_status; - mavlink_msg_gimbal_device_attitude_status_decode(&message, &attitude_status); - - Quaternion quaternion; - quaternion.w = attitude_status.q[0]; - quaternion.x = attitude_status.q[1]; - quaternion.y = attitude_status.q[2]; - quaternion.z = attitude_status.q[3]; - - EulerAngle euler_angle = to_euler_angle_from_quaternion(quaternion); - - auto telemetry_euler_angle = Telemetry::EulerAngle{}; - telemetry_euler_angle.timestamp_us = attitude_status.time_boot_ms * 1000; - telemetry_euler_angle.roll_deg = euler_angle.roll_deg; - telemetry_euler_angle.pitch_deg = euler_angle.pitch_deg; - telemetry_euler_angle.yaw_deg = euler_angle.yaw_deg; - - set_camera_attitude_euler_angle(telemetry_euler_angle); - - std::lock_guard lock(_subscription_mutex); - _camera_attitude_quaternion_subscriptions.queue( - camera_attitude_quaternion(), - [this](const auto& func) { _system_impl->call_user_callback(func); }); - - _camera_attitude_euler_angle_subscriptions.queue( - camera_attitude_euler(), - [this](const auto& func) { _system_impl->call_user_callback(func); }); -} - void TelemetryImpl::process_imu_reading_ned(const mavlink_message_t& message) { mavlink_highres_imu_t highres_imu; @@ -2136,40 +2050,6 @@ void TelemetryImpl::set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_ _fixedwing_metrics = fixedwing_metrics; } -Telemetry::Quaternion TelemetryImpl::camera_attitude_quaternion() const -{ - std::lock_guard lock(_camera_attitude_euler_angle_mutex); - - auto euler_angle = EulerAngle{}; - euler_angle.roll_deg = _camera_attitude_euler_angle.roll_deg; - euler_angle.pitch_deg = _camera_attitude_euler_angle.pitch_deg; - euler_angle.yaw_deg = _camera_attitude_euler_angle.yaw_deg; - - auto quaternion = to_quaternion_from_euler_angle(euler_angle); - - auto telemetry_quaternion = Telemetry::Quaternion{}; - telemetry_quaternion.w = quaternion.w; - telemetry_quaternion.x = quaternion.x; - telemetry_quaternion.y = quaternion.y; - telemetry_quaternion.z = quaternion.z; - telemetry_quaternion.timestamp_us = _camera_attitude_euler_angle.timestamp_us; - - return telemetry_quaternion; -} - -Telemetry::EulerAngle TelemetryImpl::camera_attitude_euler() const -{ - std::lock_guard lock(_camera_attitude_euler_angle_mutex); - - return _camera_attitude_euler_angle; -} - -void TelemetryImpl::set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle) -{ - std::lock_guard lock(_camera_attitude_euler_angle_mutex); - _camera_attitude_euler_angle = euler_angle; -} - Telemetry::VelocityNed TelemetryImpl::velocity_ned() const { std::lock_guard lock(_velocity_ned_mutex); @@ -2588,33 +2468,6 @@ void TelemetryImpl::unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle _ground_truth_subscriptions.unsubscribe(handle); } -Telemetry::AttitudeQuaternionHandle TelemetryImpl::subscribe_camera_attitude_quaternion( - const Telemetry::AttitudeQuaternionCallback& callback) -{ - std::lock_guard lock(_subscription_mutex); - return _camera_attitude_quaternion_subscriptions.subscribe(callback); -} - -void TelemetryImpl::unsubscribe_camera_attitude_quaternion( - Telemetry::AttitudeQuaternionHandle handle) -{ - std::lock_guard lock(_subscription_mutex); - _camera_attitude_quaternion_subscriptions.unsubscribe(handle); -} - -Telemetry::AttitudeEulerHandle -TelemetryImpl::subscribe_camera_attitude_euler(const Telemetry::AttitudeEulerCallback& callback) -{ - std::lock_guard lock(_subscription_mutex); - return _camera_attitude_euler_angle_subscriptions.subscribe(callback); -} - -void TelemetryImpl::unsubscribe_camera_attitude_euler(Telemetry::AttitudeEulerHandle handle) -{ - std::lock_guard lock(_subscription_mutex); - _camera_attitude_euler_angle_subscriptions.unsubscribe(handle); -} - Telemetry::VelocityNedHandle TelemetryImpl::subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback) { diff --git a/src/mavsdk/plugins/telemetry/telemetry_impl.h b/src/mavsdk/plugins/telemetry/telemetry_impl.h index 141a3e563a..1218de6bba 100644 --- a/src/mavsdk/plugins/telemetry/telemetry_impl.h +++ b/src/mavsdk/plugins/telemetry/telemetry_impl.h @@ -34,7 +34,6 @@ class TelemetryImpl : public PluginImplBase { Telemetry::Result set_rate_vtol_state(double rate_hz); Telemetry::Result set_rate_attitude_quaternion(double rate_hz); Telemetry::Result set_rate_attitude_euler(double rate_hz); - Telemetry::Result set_rate_camera_attitude(double rate_hz); Telemetry::Result set_rate_velocity_ned(double rate_hz); Telemetry::Result set_rate_imu(double rate_hz); Telemetry::Result set_rate_scaled_imu(double rate_hz); @@ -60,7 +59,6 @@ class TelemetryImpl : public PluginImplBase { void set_rate_vtol_state_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_attitude_quaternion_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_attitude_euler_async(double rate_hz, Telemetry::ResultCallback callback); - void set_rate_camera_attitude_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_imu_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_scaled_imu_async(double rate_hz, Telemetry::ResultCallback callback); @@ -94,8 +92,6 @@ class TelemetryImpl : public PluginImplBase { Telemetry::AngularVelocityBody attitude_angular_velocity_body() const; Telemetry::GroundTruth ground_truth() const; Telemetry::FixedwingMetrics fixedwing_metrics() const; - Telemetry::EulerAngle camera_attitude_euler() const; - Telemetry::Quaternion camera_attitude_quaternion() const; Telemetry::VelocityNed velocity_ned() const; Telemetry::Imu imu() const; Telemetry::Imu scaled_imu() const; @@ -146,12 +142,6 @@ class TelemetryImpl : public PluginImplBase { Telemetry::GroundTruthHandle subscribe_ground_truth(const Telemetry::GroundTruthCallback& callback); void unsubscribe_ground_truth(Telemetry::GroundTruthHandle handle); - Telemetry::AttitudeQuaternionHandle - subscribe_camera_attitude_quaternion(const Telemetry::AttitudeQuaternionCallback& callback); - void unsubscribe_camera_attitude_quaternion(Telemetry::AttitudeQuaternionHandle handle); - Telemetry::AttitudeEulerHandle - subscribe_camera_attitude_euler(const Telemetry::AttitudeEulerCallback& callback); - void unsubscribe_camera_attitude_euler(Telemetry::AttitudeEulerHandle handle); Telemetry::VelocityNedHandle subscribe_velocity_ned(const Telemetry::VelocityNedCallback& callback); void unsubscribe_velocity_ned(Telemetry::VelocityNedHandle handle); @@ -221,7 +211,6 @@ class TelemetryImpl : public PluginImplBase { void set_attitude_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body); void set_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics); void set_ground_truth(Telemetry::GroundTruth ground_truth); - void set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle); void set_velocity_ned(Telemetry::VelocityNed velocity_ned); void set_imu_reading_ned(Telemetry::Imu imu); void set_scaled_imu(Telemetry::Imu imu); @@ -251,8 +240,6 @@ class TelemetryImpl : public PluginImplBase { void process_home_position(const mavlink_message_t& message); void process_attitude(const mavlink_message_t& message); void process_attitude_quaternion(const mavlink_message_t& message); - void process_gimbal_device_attitude_status(const mavlink_message_t& message); - void process_mount_orientation(const mavlink_message_t& message); void process_imu_reading_ned(const mavlink_message_t& message); void process_scaled_imu(const mavlink_message_t& message); void process_raw_imu(const mavlink_message_t& message); @@ -341,9 +328,6 @@ class TelemetryImpl : public PluginImplBase { mutable std::mutex _attitude_euler_mutex{}; Telemetry::EulerAngle _attitude_euler{}; - mutable std::mutex _camera_attitude_euler_angle_mutex{}; - Telemetry::EulerAngle _camera_attitude_euler_angle{}; - mutable std::mutex _attitude_angular_velocity_body_mutex{}; Telemetry::AngularVelocityBody _attitude_angular_velocity_body{}; @@ -423,8 +407,6 @@ class TelemetryImpl : public PluginImplBase { CallbackList _ground_truth_subscriptions{}; CallbackList _fixedwing_metrics_subscriptions{}; CallbackList _attitude_euler_angle_subscriptions{}; - CallbackList _camera_attitude_quaternion_subscriptions{}; - CallbackList _camera_attitude_euler_angle_subscriptions{}; CallbackList _velocity_ned_subscriptions{}; CallbackList _imu_reading_ned_subscriptions{}; CallbackList _scaled_imu_subscriptions{}; diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc index eef96ca1cb..83a6c5898d 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc @@ -33,8 +33,6 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody", - "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion", - "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeEuler", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRawGps", @@ -65,7 +63,6 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SetRateVtolState", "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeQuaternion", "/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitudeEuler", - "/mavsdk.rpc.telemetry.TelemetryService/SetRateCameraAttitude", "/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed", "/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo", "/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery", @@ -101,56 +98,53 @@ TelemetryService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& c , rpcmethod_SubscribeAttitudeQuaternion_(TelemetryService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeAttitudeEuler_(TelemetryService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeAttitudeAngularVelocityBody_(TelemetryService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCameraAttitudeQuaternion_(TelemetryService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCameraAttitudeEuler_(TelemetryService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeVelocityNed_(TelemetryService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeGpsInfo_(TelemetryService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeRawGps_(TelemetryService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeBattery_(TelemetryService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeFlightMode_(TelemetryService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeHealth_(TelemetryService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeRcStatus_(TelemetryService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStatusText_(TelemetryService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeActuatorControlTarget_(TelemetryService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeActuatorOutputStatus_(TelemetryService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeOdometry_(TelemetryService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribePositionVelocityNed_(TelemetryService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeGroundTruth_(TelemetryService_method_names[23], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeFixedwingMetrics_(TelemetryService_method_names[24], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeImu_(TelemetryService_method_names[25], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeScaledImu_(TelemetryService_method_names[26], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeRawImu_(TelemetryService_method_names[27], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeHealthAllOk_(TelemetryService_method_names[28], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeUnixEpochTime_(TelemetryService_method_names[29], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeDistanceSensor_(TelemetryService_method_names[30], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeScaledPressure_(TelemetryService_method_names[31], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeHeading_(TelemetryService_method_names[32], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeAltitude_(TelemetryService_method_names[33], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SetRatePosition_(TelemetryService_method_names[34], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateHome_(TelemetryService_method_names[35], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateInAir_(TelemetryService_method_names[36], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateLandedState_(TelemetryService_method_names[37], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateVtolState_(TelemetryService_method_names[38], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateAttitudeQuaternion_(TelemetryService_method_names[39], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateAttitudeEuler_(TelemetryService_method_names[40], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateCameraAttitude_(TelemetryService_method_names[41], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateVelocityNed_(TelemetryService_method_names[42], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateGpsInfo_(TelemetryService_method_names[43], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateBattery_(TelemetryService_method_names[44], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateRcStatus_(TelemetryService_method_names[45], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateActuatorControlTarget_(TelemetryService_method_names[46], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateActuatorOutputStatus_(TelemetryService_method_names[47], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateOdometry_(TelemetryService_method_names[48], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRatePositionVelocityNed_(TelemetryService_method_names[49], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateGroundTruth_(TelemetryService_method_names[50], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateFixedwingMetrics_(TelemetryService_method_names[51], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateImu_(TelemetryService_method_names[52], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateScaledImu_(TelemetryService_method_names[53], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateRawImu_(TelemetryService_method_names[54], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateUnixEpochTime_(TelemetryService_method_names[55], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateDistanceSensor_(TelemetryService_method_names[56], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateAltitude_(TelemetryService_method_names[57], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_GetGpsGlobalOrigin_(TelemetryService_method_names[58], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeVelocityNed_(TelemetryService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeGpsInfo_(TelemetryService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeRawGps_(TelemetryService_method_names[11], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeBattery_(TelemetryService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeFlightMode_(TelemetryService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeHealth_(TelemetryService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeRcStatus_(TelemetryService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStatusText_(TelemetryService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeActuatorControlTarget_(TelemetryService_method_names[17], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeActuatorOutputStatus_(TelemetryService_method_names[18], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeOdometry_(TelemetryService_method_names[19], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribePositionVelocityNed_(TelemetryService_method_names[20], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeGroundTruth_(TelemetryService_method_names[21], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeFixedwingMetrics_(TelemetryService_method_names[22], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeImu_(TelemetryService_method_names[23], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeScaledImu_(TelemetryService_method_names[24], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeRawImu_(TelemetryService_method_names[25], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeHealthAllOk_(TelemetryService_method_names[26], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeUnixEpochTime_(TelemetryService_method_names[27], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeDistanceSensor_(TelemetryService_method_names[28], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeScaledPressure_(TelemetryService_method_names[29], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeHeading_(TelemetryService_method_names[30], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeAltitude_(TelemetryService_method_names[31], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SetRatePosition_(TelemetryService_method_names[32], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateHome_(TelemetryService_method_names[33], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateInAir_(TelemetryService_method_names[34], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateLandedState_(TelemetryService_method_names[35], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateVtolState_(TelemetryService_method_names[36], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateAttitudeQuaternion_(TelemetryService_method_names[37], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateAttitudeEuler_(TelemetryService_method_names[38], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateVelocityNed_(TelemetryService_method_names[39], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateGpsInfo_(TelemetryService_method_names[40], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateBattery_(TelemetryService_method_names[41], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateRcStatus_(TelemetryService_method_names[42], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateActuatorControlTarget_(TelemetryService_method_names[43], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateActuatorOutputStatus_(TelemetryService_method_names[44], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateOdometry_(TelemetryService_method_names[45], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRatePositionVelocityNed_(TelemetryService_method_names[46], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateGroundTruth_(TelemetryService_method_names[47], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateFixedwingMetrics_(TelemetryService_method_names[48], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateImu_(TelemetryService_method_names[49], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateScaledImu_(TelemetryService_method_names[50], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateRawImu_(TelemetryService_method_names[51], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateUnixEpochTime_(TelemetryService_method_names[52], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateDistanceSensor_(TelemetryService_method_names[53], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SetRateAltitude_(TelemetryService_method_names[54], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_GetGpsGlobalOrigin_(TelemetryService_method_names[55], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::ClientReader< ::mavsdk::rpc::telemetry::PositionResponse>* TelemetryService::Stub::SubscribePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribePositionRequest& request) { @@ -297,38 +291,6 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBody return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAttitudeAngularVelocityBody_, context, request, false, nullptr); } -::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* TelemetryService::Stub::SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>::Create(channel_.get(), rpcmethod_SubscribeCameraAttitudeQuaternion_, context, request); -} - -void TelemetryService::Stub::async::SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeCameraAttitudeQuaternion_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* TelemetryService::Stub::AsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraAttitudeQuaternion_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* TelemetryService::Stub::PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraAttitudeQuaternion_, context, request, false, nullptr); -} - -::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* TelemetryService::Stub::SubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>::Create(channel_.get(), rpcmethod_SubscribeCameraAttitudeEuler_, context, request); -} - -void TelemetryService::Stub::async::SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeCameraAttitudeEuler_, context, request, reactor); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* TelemetryService::Stub::AsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraAttitudeEuler_, context, request, true, tag); -} - -::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* TelemetryService::Stub::PrepareAsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeCameraAttitudeEuler_, context, request, false, nullptr); -} - ::grpc::ClientReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>* TelemetryService::Stub::SubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::VelocityNedResponse>::Create(channel_.get(), rpcmethod_SubscribeVelocityNed_, context, request); } @@ -858,29 +820,6 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeEule return result; } -::grpc::Status TelemetryService::Stub::SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response) { - return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRateCameraAttitude_, context, request, response); -} - -void TelemetryService::Stub::async::SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, std::function f) { - ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRateCameraAttitude_, context, request, response, std::move(f)); -} - -void TelemetryService::Stub::async::SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) { - ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRateCameraAttitude_, context, request, response, reactor); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* TelemetryService::Stub::PrepareAsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetRateCameraAttitude_, context, request); -} - -::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* TelemetryService::Stub::AsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - auto* result = - this->PrepareAsyncSetRateCameraAttitudeRaw(context, request, cq); - result->StartCall(); - return result; -} - ::grpc::Status TelemetryService::Stub::SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRateVelocityNed_, context, request, response); } @@ -1366,26 +1305,6 @@ TelemetryService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( TelemetryService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>( - [](TelemetryService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer) { - return service->SubscribeCameraAttitudeQuaternion(ctx, req, writer); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[10], - ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>( - [](TelemetryService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* writer) { - return service->SubscribeCameraAttitudeEuler(ctx, req, writer); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[11], - ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest, ::mavsdk::rpc::telemetry::VelocityNedResponse>( [](TelemetryService::Service* service, ::grpc::ServerContext* ctx, @@ -1394,7 +1313,7 @@ TelemetryService::Service::Service() { return service->SubscribeVelocityNed(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[12], + TelemetryService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( [](TelemetryService::Service* service, @@ -1404,7 +1323,7 @@ TelemetryService::Service::Service() { return service->SubscribeGpsInfo(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[13], + TelemetryService_method_names[11], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest, ::mavsdk::rpc::telemetry::RawGpsResponse>( [](TelemetryService::Service* service, @@ -1414,7 +1333,7 @@ TelemetryService::Service::Service() { return service->SubscribeRawGps(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[14], + TelemetryService_method_names[12], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>( [](TelemetryService::Service* service, @@ -1424,7 +1343,7 @@ TelemetryService::Service::Service() { return service->SubscribeBattery(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[15], + TelemetryService_method_names[13], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>( [](TelemetryService::Service* service, @@ -1434,7 +1353,7 @@ TelemetryService::Service::Service() { return service->SubscribeFlightMode(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[16], + TelemetryService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>( [](TelemetryService::Service* service, @@ -1444,7 +1363,7 @@ TelemetryService::Service::Service() { return service->SubscribeHealth(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[17], + TelemetryService_method_names[15], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>( [](TelemetryService::Service* service, @@ -1454,7 +1373,7 @@ TelemetryService::Service::Service() { return service->SubscribeRcStatus(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[18], + TelemetryService_method_names[16], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>( [](TelemetryService::Service* service, @@ -1464,7 +1383,7 @@ TelemetryService::Service::Service() { return service->SubscribeStatusText(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[19], + TelemetryService_method_names[17], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>( [](TelemetryService::Service* service, @@ -1474,7 +1393,7 @@ TelemetryService::Service::Service() { return service->SubscribeActuatorControlTarget(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[20], + TelemetryService_method_names[18], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>( [](TelemetryService::Service* service, @@ -1484,7 +1403,7 @@ TelemetryService::Service::Service() { return service->SubscribeActuatorOutputStatus(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[21], + TelemetryService_method_names[19], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeOdometryRequest, ::mavsdk::rpc::telemetry::OdometryResponse>( [](TelemetryService::Service* service, @@ -1494,7 +1413,7 @@ TelemetryService::Service::Service() { return service->SubscribeOdometry(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[22], + TelemetryService_method_names[20], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::PositionVelocityNedResponse>( [](TelemetryService::Service* service, @@ -1504,7 +1423,7 @@ TelemetryService::Service::Service() { return service->SubscribePositionVelocityNed(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[23], + TelemetryService_method_names[21], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest, ::mavsdk::rpc::telemetry::GroundTruthResponse>( [](TelemetryService::Service* service, @@ -1514,7 +1433,7 @@ TelemetryService::Service::Service() { return service->SubscribeGroundTruth(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[24], + TelemetryService_method_names[22], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::FixedwingMetricsResponse>( [](TelemetryService::Service* service, @@ -1524,7 +1443,7 @@ TelemetryService::Service::Service() { return service->SubscribeFixedwingMetrics(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[25], + TelemetryService_method_names[23], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeImuRequest, ::mavsdk::rpc::telemetry::ImuResponse>( [](TelemetryService::Service* service, @@ -1534,7 +1453,7 @@ TelemetryService::Service::Service() { return service->SubscribeImu(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[26], + TelemetryService_method_names[24], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeScaledImuRequest, ::mavsdk::rpc::telemetry::ScaledImuResponse>( [](TelemetryService::Service* service, @@ -1544,7 +1463,7 @@ TelemetryService::Service::Service() { return service->SubscribeScaledImu(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[27], + TelemetryService_method_names[25], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeRawImuRequest, ::mavsdk::rpc::telemetry::RawImuResponse>( [](TelemetryService::Service* service, @@ -1554,7 +1473,7 @@ TelemetryService::Service::Service() { return service->SubscribeRawImu(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[28], + TelemetryService_method_names[26], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest, ::mavsdk::rpc::telemetry::HealthAllOkResponse>( [](TelemetryService::Service* service, @@ -1564,7 +1483,7 @@ TelemetryService::Service::Service() { return service->SubscribeHealthAllOk(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[29], + TelemetryService_method_names[27], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::UnixEpochTimeResponse>( [](TelemetryService::Service* service, @@ -1574,7 +1493,7 @@ TelemetryService::Service::Service() { return service->SubscribeUnixEpochTime(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[30], + TelemetryService_method_names[28], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest, ::mavsdk::rpc::telemetry::DistanceSensorResponse>( [](TelemetryService::Service* service, @@ -1584,7 +1503,7 @@ TelemetryService::Service::Service() { return service->SubscribeDistanceSensor(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[31], + TelemetryService_method_names[29], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest, ::mavsdk::rpc::telemetry::ScaledPressureResponse>( [](TelemetryService::Service* service, @@ -1594,7 +1513,7 @@ TelemetryService::Service::Service() { return service->SubscribeScaledPressure(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[32], + TelemetryService_method_names[30], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeHeadingRequest, ::mavsdk::rpc::telemetry::HeadingResponse>( [](TelemetryService::Service* service, @@ -1604,7 +1523,7 @@ TelemetryService::Service::Service() { return service->SubscribeHeading(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[33], + TelemetryService_method_names[31], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>( [](TelemetryService::Service* service, @@ -1614,7 +1533,7 @@ TelemetryService::Service::Service() { return service->SubscribeAltitude(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[34], + TelemetryService_method_names[32], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1624,7 +1543,7 @@ TelemetryService::Service::Service() { return service->SetRatePosition(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[35], + TelemetryService_method_names[33], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1634,7 +1553,7 @@ TelemetryService::Service::Service() { return service->SetRateHome(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[36], + TelemetryService_method_names[34], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1644,7 +1563,7 @@ TelemetryService::Service::Service() { return service->SetRateInAir(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[37], + TelemetryService_method_names[35], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1654,7 +1573,7 @@ TelemetryService::Service::Service() { return service->SetRateLandedState(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[38], + TelemetryService_method_names[36], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1664,7 +1583,7 @@ TelemetryService::Service::Service() { return service->SetRateVtolState(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[39], + TelemetryService_method_names[37], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1674,7 +1593,7 @@ TelemetryService::Service::Service() { return service->SetRateAttitudeQuaternion(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[40], + TelemetryService_method_names[38], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1684,17 +1603,7 @@ TelemetryService::Service::Service() { return service->SetRateAttitudeEuler(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[41], - ::grpc::internal::RpcMethod::NORMAL_RPC, - new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( - [](TelemetryService::Service* service, - ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* req, - ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* resp) { - return service->SetRateCameraAttitude(ctx, req, resp); - }, this))); - AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[42], + TelemetryService_method_names[39], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1704,7 +1613,7 @@ TelemetryService::Service::Service() { return service->SetRateVelocityNed(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[43], + TelemetryService_method_names[40], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1714,7 +1623,7 @@ TelemetryService::Service::Service() { return service->SetRateGpsInfo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[44], + TelemetryService_method_names[41], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1724,7 +1633,7 @@ TelemetryService::Service::Service() { return service->SetRateBattery(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[45], + TelemetryService_method_names[42], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1734,7 +1643,7 @@ TelemetryService::Service::Service() { return service->SetRateRcStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[46], + TelemetryService_method_names[43], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1744,7 +1653,7 @@ TelemetryService::Service::Service() { return service->SetRateActuatorControlTarget(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[47], + TelemetryService_method_names[44], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1754,7 +1663,7 @@ TelemetryService::Service::Service() { return service->SetRateActuatorOutputStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[48], + TelemetryService_method_names[45], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1764,7 +1673,7 @@ TelemetryService::Service::Service() { return service->SetRateOdometry(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[49], + TelemetryService_method_names[46], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1774,7 +1683,7 @@ TelemetryService::Service::Service() { return service->SetRatePositionVelocityNed(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[50], + TelemetryService_method_names[47], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1784,7 +1693,7 @@ TelemetryService::Service::Service() { return service->SetRateGroundTruth(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[51], + TelemetryService_method_names[48], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1794,7 +1703,7 @@ TelemetryService::Service::Service() { return service->SetRateFixedwingMetrics(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[52], + TelemetryService_method_names[49], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1804,7 +1713,7 @@ TelemetryService::Service::Service() { return service->SetRateImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[53], + TelemetryService_method_names[50], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1814,7 +1723,7 @@ TelemetryService::Service::Service() { return service->SetRateScaledImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[54], + TelemetryService_method_names[51], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1824,7 +1733,7 @@ TelemetryService::Service::Service() { return service->SetRateRawImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[55], + TelemetryService_method_names[52], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1834,7 +1743,7 @@ TelemetryService::Service::Service() { return service->SetRateUnixEpochTime(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[56], + TelemetryService_method_names[53], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1844,7 +1753,7 @@ TelemetryService::Service::Service() { return service->SetRateDistanceSensor(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[57], + TelemetryService_method_names[54], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1854,7 +1763,7 @@ TelemetryService::Service::Service() { return service->SetRateAltitude(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[58], + TelemetryService_method_names[55], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](TelemetryService::Service* service, @@ -1931,20 +1840,6 @@ ::grpc::Status TelemetryService::Service::SubscribeAttitudeAngularVelocityBody(: return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status TelemetryService::Service::SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - -::grpc::Status TelemetryService::Service::SubscribeCameraAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* writer) { - (void) context; - (void) request; - (void) writer; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - ::grpc::Status TelemetryService::Service::SubscribeVelocityNed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::VelocityNedResponse>* writer) { (void) context; (void) request; @@ -2155,13 +2050,6 @@ ::grpc::Status TelemetryService::Service::SetRateAttitudeEuler(::grpc::ServerCon return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status TelemetryService::Service::SetRateCameraAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response) { - (void) context; - (void) request; - (void) response; - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); -} - ::grpc::Status TelemetryService::Service::SetRateVelocityNed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response) { (void) context; (void) request; diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h index 4fd5e649cb..e31aa2afea 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h @@ -130,26 +130,6 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> PrepareAsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq)); } - // Subscribe to 'camera attitude' updates (quaternion). - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(SubscribeCameraAttitudeQuaternionRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> AsyncSubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(AsyncSubscribeCameraAttitudeQuaternionRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> PrepareAsyncSubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(context, request, cq)); - } - // Subscribe to 'camera attitude' updates (Euler). - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(SubscribeCameraAttitudeEulerRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> AsyncSubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(AsyncSubscribeCameraAttitudeEulerRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> PrepareAsyncSubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(PrepareAsyncSubscribeCameraAttitudeEulerRaw(context, request, cq)); - } // Subscribe to 'ground speed' updates (NED). std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::VelocityNedResponse>> SubscribeVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::VelocityNedResponse>>(SubscribeVelocityNedRaw(context, request)); @@ -437,13 +417,6 @@ class TelemetryService final { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>>(PrepareAsyncSetRateAttitudeEulerRaw(context, request, cq)); } // Set rate of camera attitude updates. - virtual ::grpc::Status SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response) = 0; - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>> AsyncSetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>>(AsyncSetRateCameraAttitudeRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>> PrepareAsyncSetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>>(PrepareAsyncSetRateCameraAttitudeRaw(context, request, cq)); - } // Set rate to 'ground speed' updates (NED). virtual ::grpc::Status SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>> AsyncSetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) { @@ -601,10 +574,6 @@ class TelemetryService final { virtual void SubscribeAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* reactor) = 0; // Subscribe to 'attitude' updates (angular velocity) virtual void SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* reactor) = 0; - // Subscribe to 'camera attitude' updates (quaternion). - virtual void SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* reactor) = 0; - // Subscribe to 'camera attitude' updates (Euler). - virtual void SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* reactor) = 0; // Subscribe to 'ground speed' updates (NED). virtual void SubscribeVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::VelocityNedResponse>* reactor) = 0; // Subscribe to 'GPS info' updates. @@ -673,8 +642,6 @@ class TelemetryService final { virtual void SetRateAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response, std::function) = 0; virtual void SetRateAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Set rate of camera attitude updates. - virtual void SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, std::function) = 0; - virtual void SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Set rate to 'ground speed' updates (NED). virtual void SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response, std::function) = 0; virtual void SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -758,12 +725,6 @@ class TelemetryService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* SubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* AsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* AsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* SubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* AsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* PrepareAsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::VelocityNedResponse>* SubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::VelocityNedResponse>* AsyncSubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::VelocityNedResponse>* PrepareAsyncSubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -847,8 +808,6 @@ class TelemetryService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>* PrepareAsyncSetRateAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* AsyncSetRateAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* PrepareAsyncSetRateAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* AsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* PrepareAsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* AsyncSetRateVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* PrepareAsyncSetRateVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>* AsyncSetRateGpsInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -968,24 +927,6 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> PrepareAsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(SubscribeCameraAttitudeQuaternionRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> AsyncSubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(AsyncSubscribeCameraAttitudeQuaternionRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> PrepareAsyncSubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(SubscribeCameraAttitudeEulerRaw(context, request)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> AsyncSubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(AsyncSubscribeCameraAttitudeEulerRaw(context, request, cq, tag)); - } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>> PrepareAsyncSubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>>(PrepareAsyncSubscribeCameraAttitudeEulerRaw(context, request, cq)); - } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>> SubscribeVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>>(SubscribeVelocityNedRaw(context, request)); } @@ -1242,13 +1183,6 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>> PrepareAsyncSetRateAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>>(PrepareAsyncSetRateAttitudeEulerRaw(context, request, cq)); } - ::grpc::Status SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response) override; - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>> AsyncSetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>>(AsyncSetRateCameraAttitudeRaw(context, request, cq)); - } - std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>> PrepareAsyncSetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>>(PrepareAsyncSetRateCameraAttitudeRaw(context, request, cq)); - } ::grpc::Status SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>> AsyncSetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>>(AsyncSetRateVelocityNedRaw(context, request, cq)); @@ -1380,8 +1314,6 @@ class TelemetryService final { void SubscribeAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeQuaternionResponse>* reactor) override; void SubscribeAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* reactor) override; void SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* reactor) override; - void SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* reactor) override; - void SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* reactor) override; void SubscribeVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::VelocityNedResponse>* reactor) override; void SubscribeGpsInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::GpsInfoResponse>* reactor) override; void SubscribeRawGps(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::RawGpsResponse>* reactor) override; @@ -1419,8 +1351,6 @@ class TelemetryService final { void SetRateAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetRateAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response, std::function) override; void SetRateAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, std::function) override; - void SetRateCameraAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response, std::function) override; void SetRateVelocityNed(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetRateGpsInfo(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest* request, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse* response, std::function) override; @@ -1493,12 +1423,6 @@ class TelemetryService final { ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* SubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* AsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* AsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* SubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* AsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* PrepareAsyncSubscribeCameraAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>* SubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>* AsyncSubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::VelocityNedResponse>* PrepareAsyncSubscribeVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest& request, ::grpc::CompletionQueue* cq) override; @@ -1582,8 +1506,6 @@ class TelemetryService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>* PrepareAsyncSetRateAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* AsyncSetRateAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* PrepareAsyncSetRateAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* AsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* PrepareAsyncSetRateCameraAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* AsyncSetRateVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* PrepareAsyncSetRateVelocityNedRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>* AsyncSetRateGpsInfoRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest& request, ::grpc::CompletionQueue* cq) override; @@ -1627,8 +1549,6 @@ class TelemetryService final { const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeQuaternion_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeEuler_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeAngularVelocityBody_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeCameraAttitudeQuaternion_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeCameraAttitudeEuler_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeVelocityNed_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeGpsInfo_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeRawGps_; @@ -1659,7 +1579,6 @@ class TelemetryService final { const ::grpc::internal::RpcMethod rpcmethod_SetRateVtolState_; const ::grpc::internal::RpcMethod rpcmethod_SetRateAttitudeQuaternion_; const ::grpc::internal::RpcMethod rpcmethod_SetRateAttitudeEuler_; - const ::grpc::internal::RpcMethod rpcmethod_SetRateCameraAttitude_; const ::grpc::internal::RpcMethod rpcmethod_SetRateVelocityNed_; const ::grpc::internal::RpcMethod rpcmethod_SetRateGpsInfo_; const ::grpc::internal::RpcMethod rpcmethod_SetRateBattery_; @@ -1702,10 +1621,6 @@ class TelemetryService final { virtual ::grpc::Status SubscribeAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* writer); // Subscribe to 'attitude' updates (angular velocity) virtual ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer); - // Subscribe to 'camera attitude' updates (quaternion). - virtual ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer); - // Subscribe to 'camera attitude' updates (Euler). - virtual ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* writer); // Subscribe to 'ground speed' updates (NED). virtual ::grpc::Status SubscribeVelocityNed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::VelocityNedResponse>* writer); // Subscribe to 'GPS info' updates. @@ -1767,7 +1682,6 @@ class TelemetryService final { // Set rate to 'attitude quaternion' updates. virtual ::grpc::Status SetRateAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response); // Set rate of camera attitude updates. - virtual ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response); // Set rate to 'ground speed' updates (NED). virtual ::grpc::Status SetRateVelocityNed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response); // Set rate to 'GPS info' updates. @@ -1984,52 +1898,12 @@ class TelemetryService final { } }; template - class WithAsyncMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodAsync(9); - } - ~WithAsyncMethod_SubscribeCameraAttitudeQuaternion() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SubscribeCameraAttitudeEuler : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodAsync(10); - } - ~WithAsyncMethod_SubscribeCameraAttitudeEuler() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeCameraAttitudeEuler(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* 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); - } - }; - template class WithAsyncMethod_SubscribeVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodAsync(11); + ::grpc::Service::MarkMethodAsync(9); } ~WithAsyncMethod_SubscribeVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2040,7 +1914,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeVelocityNed(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::VelocityNedResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2049,7 +1923,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodAsync(12); + ::grpc::Service::MarkMethodAsync(10); } ~WithAsyncMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -2060,7 +1934,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGpsInfo(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::GpsInfoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2069,7 +1943,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodAsync(13); + ::grpc::Service::MarkMethodAsync(11); } ~WithAsyncMethod_SubscribeRawGps() override { BaseClassMustBeDerivedFromService(this); @@ -2080,7 +1954,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRawGps(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::RawGpsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2089,7 +1963,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodAsync(14); + ::grpc::Service::MarkMethodAsync(12); } ~WithAsyncMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -2100,7 +1974,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeBattery(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeBatteryRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::BatteryResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2109,7 +1983,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodAsync(15); + ::grpc::Service::MarkMethodAsync(13); } ~WithAsyncMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -2120,7 +1994,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFlightMode(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::FlightModeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2129,7 +2003,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodAsync(16); + ::grpc::Service::MarkMethodAsync(14); } ~WithAsyncMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -2140,7 +2014,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealth(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::HealthResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2149,7 +2023,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodAsync(17); + ::grpc::Service::MarkMethodAsync(15); } ~WithAsyncMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2160,7 +2034,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRcStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::RcStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2169,7 +2043,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodAsync(18); + ::grpc::Service::MarkMethodAsync(16); } ~WithAsyncMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -2180,7 +2054,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatusText(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::StatusTextResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2189,7 +2063,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodAsync(19); + ::grpc::Service::MarkMethodAsync(17); } ~WithAsyncMethod_SubscribeActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -2200,7 +2074,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeActuatorControlTarget(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2209,7 +2083,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodAsync(20); + ::grpc::Service::MarkMethodAsync(18); } ~WithAsyncMethod_SubscribeActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2220,7 +2094,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeActuatorOutputStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2229,7 +2103,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodAsync(21); + ::grpc::Service::MarkMethodAsync(19); } ~WithAsyncMethod_SubscribeOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -2240,7 +2114,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeOdometry(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeOdometryRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::OdometryResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(21, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2249,7 +2123,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodAsync(22); + ::grpc::Service::MarkMethodAsync(20); } ~WithAsyncMethod_SubscribePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2260,7 +2134,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribePositionVelocityNed(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::PositionVelocityNedResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(22, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2269,7 +2143,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodAsync(23); + ::grpc::Service::MarkMethodAsync(21); } ~WithAsyncMethod_SubscribeGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -2280,7 +2154,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGroundTruth(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::GroundTruthResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(23, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(21, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2289,7 +2163,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodAsync(24); + ::grpc::Service::MarkMethodAsync(22); } ~WithAsyncMethod_SubscribeFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -2300,7 +2174,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFixedwingMetrics(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::FixedwingMetricsResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(24, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(22, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2309,7 +2183,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeImu() { - ::grpc::Service::MarkMethodAsync(25); + ::grpc::Service::MarkMethodAsync(23); } ~WithAsyncMethod_SubscribeImu() override { BaseClassMustBeDerivedFromService(this); @@ -2320,7 +2194,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeImuRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ImuResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(25, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(23, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2329,7 +2203,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodAsync(26); + ::grpc::Service::MarkMethodAsync(24); } ~WithAsyncMethod_SubscribeScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -2340,7 +2214,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeScaledImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeScaledImuRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ScaledImuResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(26, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(24, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2349,7 +2223,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodAsync(27); + ::grpc::Service::MarkMethodAsync(25); } ~WithAsyncMethod_SubscribeRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -2360,7 +2234,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRawImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeRawImuRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::RawImuResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(27, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(25, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2369,7 +2243,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodAsync(28); + ::grpc::Service::MarkMethodAsync(26); } ~WithAsyncMethod_SubscribeHealthAllOk() override { BaseClassMustBeDerivedFromService(this); @@ -2380,7 +2254,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealthAllOk(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::HealthAllOkResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(28, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(26, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2389,7 +2263,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodAsync(29); + ::grpc::Service::MarkMethodAsync(27); } ~WithAsyncMethod_SubscribeUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -2400,7 +2274,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeUnixEpochTime(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::UnixEpochTimeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(29, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(27, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2409,7 +2283,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodAsync(30); + ::grpc::Service::MarkMethodAsync(28); } ~WithAsyncMethod_SubscribeDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -2420,7 +2294,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeDistanceSensor(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::DistanceSensorResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(30, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(28, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2429,7 +2303,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodAsync(31); + ::grpc::Service::MarkMethodAsync(29); } ~WithAsyncMethod_SubscribeScaledPressure() override { BaseClassMustBeDerivedFromService(this); @@ -2440,7 +2314,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeScaledPressure(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ScaledPressureResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(31, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(29, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2449,7 +2323,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodAsync(32); + ::grpc::Service::MarkMethodAsync(30); } ~WithAsyncMethod_SubscribeHeading() override { BaseClassMustBeDerivedFromService(this); @@ -2460,7 +2334,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHeading(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::HeadingResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(32, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(30, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2469,7 +2343,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodAsync(33); + ::grpc::Service::MarkMethodAsync(31); } ~WithAsyncMethod_SubscribeAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -2480,7 +2354,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeAltitude(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(33, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(31, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -2489,7 +2363,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRatePosition() { - ::grpc::Service::MarkMethodAsync(34); + ::grpc::Service::MarkMethodAsync(32); } ~WithAsyncMethod_SetRatePosition() override { BaseClassMustBeDerivedFromService(this); @@ -2500,7 +2374,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRatePosition(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRatePositionResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(32, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2509,7 +2383,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateHome() { - ::grpc::Service::MarkMethodAsync(35); + ::grpc::Service::MarkMethodAsync(33); } ~WithAsyncMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); @@ -2520,7 +2394,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateHome(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateHomeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateHomeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(33, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2529,7 +2403,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateInAir() { - ::grpc::Service::MarkMethodAsync(36); + ::grpc::Service::MarkMethodAsync(34); } ~WithAsyncMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -2540,7 +2414,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateInAir(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateInAirRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateInAirResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(36, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2549,7 +2423,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodAsync(37); + ::grpc::Service::MarkMethodAsync(35); } ~WithAsyncMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -2560,7 +2434,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateLandedState(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateLandedStateRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(37, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2569,7 +2443,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodAsync(38); + ::grpc::Service::MarkMethodAsync(36); } ~WithAsyncMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -2580,7 +2454,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateVtolState(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateVtolStateRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(38, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(36, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2589,7 +2463,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodAsync(39); + ::grpc::Service::MarkMethodAsync(37); } ~WithAsyncMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -2600,7 +2474,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAttitudeQuaternion(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(39, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(37, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2609,7 +2483,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodAsync(40); + ::grpc::Service::MarkMethodAsync(38); } ~WithAsyncMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -2620,27 +2494,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAttitudeEuler(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(40, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithAsyncMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithAsyncMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodAsync(41); - } - ~WithAsyncMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSetRateCameraAttitude(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(41, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(38, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2649,7 +2503,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodAsync(42); + ::grpc::Service::MarkMethodAsync(39); } ~WithAsyncMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2660,7 +2514,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateVelocityNed(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(42, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(39, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2669,7 +2523,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodAsync(43); + ::grpc::Service::MarkMethodAsync(40); } ~WithAsyncMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -2680,7 +2534,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateGpsInfo(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(43, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(40, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2689,7 +2543,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateBattery() { - ::grpc::Service::MarkMethodAsync(44); + ::grpc::Service::MarkMethodAsync(41); } ~WithAsyncMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -2700,7 +2554,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateBattery(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateBatteryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateBatteryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(44, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(41, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2709,7 +2563,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodAsync(45); + ::grpc::Service::MarkMethodAsync(42); } ~WithAsyncMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2720,7 +2574,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateRcStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateRcStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(45, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(42, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2729,7 +2583,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodAsync(46); + ::grpc::Service::MarkMethodAsync(43); } ~WithAsyncMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -2740,7 +2594,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateActuatorControlTarget(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(46, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(43, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2749,7 +2603,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodAsync(47); + ::grpc::Service::MarkMethodAsync(44); } ~WithAsyncMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2760,7 +2614,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateActuatorOutputStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(47, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(44, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2769,7 +2623,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodAsync(48); + ::grpc::Service::MarkMethodAsync(45); } ~WithAsyncMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -2780,7 +2634,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateOdometry(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateOdometryRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateOdometryResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(48, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(45, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2789,7 +2643,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodAsync(49); + ::grpc::Service::MarkMethodAsync(46); } ~WithAsyncMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2800,7 +2654,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRatePositionVelocityNed(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(49, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(46, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2809,7 +2663,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodAsync(50); + ::grpc::Service::MarkMethodAsync(47); } ~WithAsyncMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -2820,7 +2674,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateGroundTruth(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(50, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(47, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2829,7 +2683,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodAsync(51); + ::grpc::Service::MarkMethodAsync(48); } ~WithAsyncMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -2840,7 +2694,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateFixedwingMetrics(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(51, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(48, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2849,7 +2703,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateImu() { - ::grpc::Service::MarkMethodAsync(52); + ::grpc::Service::MarkMethodAsync(49); } ~WithAsyncMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -2860,7 +2714,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateImuRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateImuResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(52, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(49, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2869,7 +2723,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodAsync(53); + ::grpc::Service::MarkMethodAsync(50); } ~WithAsyncMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -2880,7 +2734,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateScaledImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateScaledImuRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(53, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(50, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2889,7 +2743,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodAsync(54); + ::grpc::Service::MarkMethodAsync(51); } ~WithAsyncMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -2900,7 +2754,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateRawImu(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateRawImuRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateRawImuResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(54, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(51, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2909,7 +2763,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodAsync(55); + ::grpc::Service::MarkMethodAsync(52); } ~WithAsyncMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -2920,7 +2774,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateUnixEpochTime(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(55, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(52, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2929,7 +2783,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodAsync(56); + ::grpc::Service::MarkMethodAsync(53); } ~WithAsyncMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -2940,7 +2794,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateDistanceSensor(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(56, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(53, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2949,7 +2803,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodAsync(57); + ::grpc::Service::MarkMethodAsync(54); } ~WithAsyncMethod_SetRateAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -2960,7 +2814,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAltitude(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(57, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(54, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2969,7 +2823,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodAsync(58); + ::grpc::Service::MarkMethodAsync(55); } ~WithAsyncMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -2980,10 +2834,10 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestGetGpsGlobalOrigin(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(58, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(55, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; + typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SubscribePosition : public BaseClass { private: @@ -3183,92 +3037,48 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* /*request*/) { return nullptr; } }; template - class WithCallbackMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { + class WithCallbackMethod_SubscribeVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_SubscribeCameraAttitudeQuaternion() { + WithCallbackMethod_SubscribeVelocityNed() { ::grpc::Service::MarkMethodCallback(9, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>( + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest, ::mavsdk::rpc::telemetry::VelocityNedResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request) { return this->SubscribeCameraAttitudeQuaternion(context, request); })); + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request) { return this->SubscribeVelocityNed(context, request); })); } - ~WithCallbackMethod_SubscribeCameraAttitudeQuaternion() override { + ~WithCallbackMethod_SubscribeVelocityNed() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { + ::grpc::Status SubscribeVelocityNed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::VelocityNedResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* SubscribeCameraAttitudeQuaternion( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/) { return nullptr; } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::VelocityNedResponse>* SubscribeVelocityNed( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* /*request*/) { return nullptr; } }; template - class WithCallbackMethod_SubscribeCameraAttitudeEuler : public BaseClass { + class WithCallbackMethod_SubscribeGpsInfo : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_SubscribeCameraAttitudeEuler() { + WithCallbackMethod_SubscribeGpsInfo() { ::grpc::Service::MarkMethodCallback(10, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>( + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request) { return this->SubscribeCameraAttitudeEuler(context, request); })); + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* request) { return this->SubscribeGpsInfo(context, request); })); } - ~WithCallbackMethod_SubscribeCameraAttitudeEuler() override { + ~WithCallbackMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { + ::grpc::Status SubscribeGpsInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::GpsInfoResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* SubscribeCameraAttitudeEuler( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/) { return nullptr; } - }; - template - class WithCallbackMethod_SubscribeVelocityNed : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodCallback(11, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest, ::mavsdk::rpc::telemetry::VelocityNedResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* request) { return this->SubscribeVelocityNed(context, request); })); - } - ~WithCallbackMethod_SubscribeVelocityNed() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeVelocityNed(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::VelocityNedResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::VelocityNedResponse>* SubscribeVelocityNed( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* /*request*/) { return nullptr; } - }; - template - class WithCallbackMethod_SubscribeGpsInfo : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodCallback(12, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* request) { return this->SubscribeGpsInfo(context, request); })); - } - ~WithCallbackMethod_SubscribeGpsInfo() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeGpsInfo(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::GpsInfoResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::GpsInfoResponse>* SubscribeGpsInfo( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* /*request*/) { return nullptr; } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::GpsInfoResponse>* SubscribeGpsInfo( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* /*request*/) { return nullptr; } }; template class WithCallbackMethod_SubscribeRawGps : public BaseClass { @@ -3276,7 +3086,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodCallback(13, + ::grpc::Service::MarkMethodCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest, ::mavsdk::rpc::telemetry::RawGpsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest* request) { return this->SubscribeRawGps(context, request); })); @@ -3298,7 +3108,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodCallback(14, + ::grpc::Service::MarkMethodCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeBatteryRequest* request) { return this->SubscribeBattery(context, request); })); @@ -3320,7 +3130,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodCallback(15, + ::grpc::Service::MarkMethodCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest* request) { return this->SubscribeFlightMode(context, request); })); @@ -3342,7 +3152,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodCallback(16, + ::grpc::Service::MarkMethodCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request) { return this->SubscribeHealth(context, request); })); @@ -3364,7 +3174,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodCallback(17, + ::grpc::Service::MarkMethodCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request) { return this->SubscribeRcStatus(context, request); })); @@ -3386,7 +3196,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodCallback(18, + ::grpc::Service::MarkMethodCallback(16, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request) { return this->SubscribeStatusText(context, request); })); @@ -3408,7 +3218,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodCallback(19, + ::grpc::Service::MarkMethodCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request) { return this->SubscribeActuatorControlTarget(context, request); })); @@ -3430,7 +3240,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodCallback(20, + ::grpc::Service::MarkMethodCallback(18, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request) { return this->SubscribeActuatorOutputStatus(context, request); })); @@ -3452,7 +3262,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodCallback(21, + ::grpc::Service::MarkMethodCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeOdometryRequest, ::mavsdk::rpc::telemetry::OdometryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeOdometryRequest* request) { return this->SubscribeOdometry(context, request); })); @@ -3474,7 +3284,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodCallback(22, + ::grpc::Service::MarkMethodCallback(20, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::PositionVelocityNedResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest* request) { return this->SubscribePositionVelocityNed(context, request); })); @@ -3496,7 +3306,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodCallback(23, + ::grpc::Service::MarkMethodCallback(21, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest, ::mavsdk::rpc::telemetry::GroundTruthResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest* request) { return this->SubscribeGroundTruth(context, request); })); @@ -3518,7 +3328,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodCallback(24, + ::grpc::Service::MarkMethodCallback(22, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::FixedwingMetricsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest* request) { return this->SubscribeFixedwingMetrics(context, request); })); @@ -3540,7 +3350,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeImu() { - ::grpc::Service::MarkMethodCallback(25, + ::grpc::Service::MarkMethodCallback(23, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeImuRequest, ::mavsdk::rpc::telemetry::ImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeImuRequest* request) { return this->SubscribeImu(context, request); })); @@ -3562,7 +3372,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodCallback(26, + ::grpc::Service::MarkMethodCallback(24, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeScaledImuRequest, ::mavsdk::rpc::telemetry::ScaledImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeScaledImuRequest* request) { return this->SubscribeScaledImu(context, request); })); @@ -3584,7 +3394,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodCallback(27, + ::grpc::Service::MarkMethodCallback(25, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRawImuRequest, ::mavsdk::rpc::telemetry::RawImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeRawImuRequest* request) { return this->SubscribeRawImu(context, request); })); @@ -3606,7 +3416,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodCallback(28, + ::grpc::Service::MarkMethodCallback(26, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest, ::mavsdk::rpc::telemetry::HealthAllOkResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest* request) { return this->SubscribeHealthAllOk(context, request); })); @@ -3628,7 +3438,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodCallback(29, + ::grpc::Service::MarkMethodCallback(27, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::UnixEpochTimeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest* request) { return this->SubscribeUnixEpochTime(context, request); })); @@ -3650,7 +3460,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodCallback(30, + ::grpc::Service::MarkMethodCallback(28, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest, ::mavsdk::rpc::telemetry::DistanceSensorResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest* request) { return this->SubscribeDistanceSensor(context, request); })); @@ -3672,7 +3482,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodCallback(31, + ::grpc::Service::MarkMethodCallback(29, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest, ::mavsdk::rpc::telemetry::ScaledPressureResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest* request) { return this->SubscribeScaledPressure(context, request); })); @@ -3694,7 +3504,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodCallback(32, + ::grpc::Service::MarkMethodCallback(30, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHeadingRequest, ::mavsdk::rpc::telemetry::HeadingResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* request) { return this->SubscribeHeading(context, request); })); @@ -3716,7 +3526,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodCallback(33, + ::grpc::Service::MarkMethodCallback(31, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request) { return this->SubscribeAltitude(context, request); })); @@ -3738,13 +3548,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRatePosition() { - ::grpc::Service::MarkMethodCallback(34, + ::grpc::Service::MarkMethodCallback(32, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response) { return this->SetRatePosition(context, request, response); }));} void SetMessageAllocatorFor_SetRatePosition( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(34); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(32); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3765,13 +3575,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateHome() { - ::grpc::Service::MarkMethodCallback(35, + ::grpc::Service::MarkMethodCallback(33, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateHomeRequest* request, ::mavsdk::rpc::telemetry::SetRateHomeResponse* response) { return this->SetRateHome(context, request, response); }));} void SetMessageAllocatorFor_SetRateHome( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(35); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(33); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3792,13 +3602,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateInAir() { - ::grpc::Service::MarkMethodCallback(36, + ::grpc::Service::MarkMethodCallback(34, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateInAirRequest* request, ::mavsdk::rpc::telemetry::SetRateInAirResponse* response) { return this->SetRateInAir(context, request, response); }));} void SetMessageAllocatorFor_SetRateInAir( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(36); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(34); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3819,13 +3629,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodCallback(37, + ::grpc::Service::MarkMethodCallback(35, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateLandedStateRequest* request, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse* response) { return this->SetRateLandedState(context, request, response); }));} void SetMessageAllocatorFor_SetRateLandedState( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(37); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(35); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3846,13 +3656,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodCallback(38, + ::grpc::Service::MarkMethodCallback(36, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateVtolStateRequest* request, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse* response) { return this->SetRateVtolState(context, request, response); }));} void SetMessageAllocatorFor_SetRateVtolState( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(38); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(36); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3873,13 +3683,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodCallback(39, + ::grpc::Service::MarkMethodCallback(37, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse* response) { return this->SetRateAttitudeQuaternion(context, request, response); }));} void SetMessageAllocatorFor_SetRateAttitudeQuaternion( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(39); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(37); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3900,13 +3710,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodCallback(40, + ::grpc::Service::MarkMethodCallback(38, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* request, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* response) { return this->SetRateAttitudeEuler(context, request, response); }));} void SetMessageAllocatorFor_SetRateAttitudeEuler( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(40); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(38); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3922,45 +3732,18 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse* /*response*/) { return nullptr; } }; template - class WithCallbackMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithCallbackMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodCallback(41, - new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>( - [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* response) { return this->SetRateCameraAttitude(context, request, response); }));} - void SetMessageAllocatorFor_SetRateCameraAttitude( - ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(41); - static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>*>(handler) - ->SetMessageAllocator(allocator); - } - ~WithCallbackMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SetRateCameraAttitude( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) { return nullptr; } - }; - template class WithCallbackMethod_SetRateVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodCallback(42, + ::grpc::Service::MarkMethodCallback(39, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse* response) { return this->SetRateVelocityNed(context, request, response); }));} void SetMessageAllocatorFor_SetRateVelocityNed( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(42); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(39); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3981,13 +3764,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodCallback(43, + ::grpc::Service::MarkMethodCallback(40, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest* request, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse* response) { return this->SetRateGpsInfo(context, request, response); }));} void SetMessageAllocatorFor_SetRateGpsInfo( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(43); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(40); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4008,13 +3791,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateBattery() { - ::grpc::Service::MarkMethodCallback(44, + ::grpc::Service::MarkMethodCallback(41, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateBatteryRequest* request, ::mavsdk::rpc::telemetry::SetRateBatteryResponse* response) { return this->SetRateBattery(context, request, response); }));} void SetMessageAllocatorFor_SetRateBattery( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(44); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(41); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4035,13 +3818,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodCallback(45, + ::grpc::Service::MarkMethodCallback(42, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateRcStatusRequest* request, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse* response) { return this->SetRateRcStatus(context, request, response); }));} void SetMessageAllocatorFor_SetRateRcStatus( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(45); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(42); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4062,13 +3845,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodCallback(46, + ::grpc::Service::MarkMethodCallback(43, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest* request, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse* response) { return this->SetRateActuatorControlTarget(context, request, response); }));} void SetMessageAllocatorFor_SetRateActuatorControlTarget( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(46); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(43); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4089,13 +3872,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodCallback(47, + ::grpc::Service::MarkMethodCallback(44, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest* request, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse* response) { return this->SetRateActuatorOutputStatus(context, request, response); }));} void SetMessageAllocatorFor_SetRateActuatorOutputStatus( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(47); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(44); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4116,13 +3899,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodCallback(48, + ::grpc::Service::MarkMethodCallback(45, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateOdometryRequest* request, ::mavsdk::rpc::telemetry::SetRateOdometryResponse* response) { return this->SetRateOdometry(context, request, response); }));} void SetMessageAllocatorFor_SetRateOdometry( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(48); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(45); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4143,13 +3926,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodCallback(49, + ::grpc::Service::MarkMethodCallback(46, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse* response) { return this->SetRatePositionVelocityNed(context, request, response); }));} void SetMessageAllocatorFor_SetRatePositionVelocityNed( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(49); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(46); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4170,13 +3953,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodCallback(50, + ::grpc::Service::MarkMethodCallback(47, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest* request, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse* response) { return this->SetRateGroundTruth(context, request, response); }));} void SetMessageAllocatorFor_SetRateGroundTruth( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(50); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(47); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4197,13 +3980,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodCallback(51, + ::grpc::Service::MarkMethodCallback(48, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest* request, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse* response) { return this->SetRateFixedwingMetrics(context, request, response); }));} void SetMessageAllocatorFor_SetRateFixedwingMetrics( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(51); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(48); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4224,13 +4007,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateImu() { - ::grpc::Service::MarkMethodCallback(52, + ::grpc::Service::MarkMethodCallback(49, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateImuRequest* request, ::mavsdk::rpc::telemetry::SetRateImuResponse* response) { return this->SetRateImu(context, request, response); }));} void SetMessageAllocatorFor_SetRateImu( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(52); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(49); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4251,13 +4034,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodCallback(53, + ::grpc::Service::MarkMethodCallback(50, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateScaledImuRequest* request, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse* response) { return this->SetRateScaledImu(context, request, response); }));} void SetMessageAllocatorFor_SetRateScaledImu( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(53); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(50); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4278,13 +4061,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodCallback(54, + ::grpc::Service::MarkMethodCallback(51, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateRawImuRequest* request, ::mavsdk::rpc::telemetry::SetRateRawImuResponse* response) { return this->SetRateRawImu(context, request, response); }));} void SetMessageAllocatorFor_SetRateRawImu( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(54); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(51); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4305,13 +4088,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodCallback(55, + ::grpc::Service::MarkMethodCallback(52, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest* request, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse* response) { return this->SetRateUnixEpochTime(context, request, response); }));} void SetMessageAllocatorFor_SetRateUnixEpochTime( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(55); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(52); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4332,13 +4115,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodCallback(56, + ::grpc::Service::MarkMethodCallback(53, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response) { return this->SetRateDistanceSensor(context, request, response); }));} void SetMessageAllocatorFor_SetRateDistanceSensor( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(56); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(53); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4359,13 +4142,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodCallback(57, + ::grpc::Service::MarkMethodCallback(54, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response) { return this->SetRateAltitude(context, request, response); }));} void SetMessageAllocatorFor_SetRateAltitude( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(57); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(54); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4386,13 +4169,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodCallback(58, + ::grpc::Service::MarkMethodCallback(55, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response) { return this->GetGpsGlobalOrigin(context, request, response); }));} void SetMessageAllocatorFor_GetGpsGlobalOrigin( ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(58); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(55); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4407,7 +4190,7 @@ class TelemetryService final { virtual ::grpc::ServerUnaryReactor* GetGpsGlobalOrigin( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* /*request*/, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > CallbackService; + typedef WithCallbackMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SubscribePosition : public BaseClass { @@ -4563,46 +4346,12 @@ class TelemetryService final { } }; template - class WithGenericMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodGeneric(9); - } - ~WithGenericMethod_SubscribeCameraAttitudeQuaternion() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template - class WithGenericMethod_SubscribeCameraAttitudeEuler : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodGeneric(10); - } - ~WithGenericMethod_SubscribeCameraAttitudeEuler() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithGenericMethod_SubscribeVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodGeneric(11); + ::grpc::Service::MarkMethodGeneric(9); } ~WithGenericMethod_SubscribeVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -4619,7 +4368,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodGeneric(12); + ::grpc::Service::MarkMethodGeneric(10); } ~WithGenericMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -4636,7 +4385,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodGeneric(13); + ::grpc::Service::MarkMethodGeneric(11); } ~WithGenericMethod_SubscribeRawGps() override { BaseClassMustBeDerivedFromService(this); @@ -4653,7 +4402,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodGeneric(14); + ::grpc::Service::MarkMethodGeneric(12); } ~WithGenericMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -4670,7 +4419,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodGeneric(15); + ::grpc::Service::MarkMethodGeneric(13); } ~WithGenericMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -4687,7 +4436,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodGeneric(16); + ::grpc::Service::MarkMethodGeneric(14); } ~WithGenericMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -4704,7 +4453,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodGeneric(17); + ::grpc::Service::MarkMethodGeneric(15); } ~WithGenericMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -4721,7 +4470,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodGeneric(18); + ::grpc::Service::MarkMethodGeneric(16); } ~WithGenericMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -4738,7 +4487,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodGeneric(19); + ::grpc::Service::MarkMethodGeneric(17); } ~WithGenericMethod_SubscribeActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -4755,7 +4504,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodGeneric(20); + ::grpc::Service::MarkMethodGeneric(18); } ~WithGenericMethod_SubscribeActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -4772,7 +4521,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodGeneric(21); + ::grpc::Service::MarkMethodGeneric(19); } ~WithGenericMethod_SubscribeOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -4789,7 +4538,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodGeneric(22); + ::grpc::Service::MarkMethodGeneric(20); } ~WithGenericMethod_SubscribePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -4806,7 +4555,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodGeneric(23); + ::grpc::Service::MarkMethodGeneric(21); } ~WithGenericMethod_SubscribeGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -4823,7 +4572,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodGeneric(24); + ::grpc::Service::MarkMethodGeneric(22); } ~WithGenericMethod_SubscribeFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -4840,7 +4589,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeImu() { - ::grpc::Service::MarkMethodGeneric(25); + ::grpc::Service::MarkMethodGeneric(23); } ~WithGenericMethod_SubscribeImu() override { BaseClassMustBeDerivedFromService(this); @@ -4857,7 +4606,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodGeneric(26); + ::grpc::Service::MarkMethodGeneric(24); } ~WithGenericMethod_SubscribeScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -4874,7 +4623,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodGeneric(27); + ::grpc::Service::MarkMethodGeneric(25); } ~WithGenericMethod_SubscribeRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -4891,7 +4640,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodGeneric(28); + ::grpc::Service::MarkMethodGeneric(26); } ~WithGenericMethod_SubscribeHealthAllOk() override { BaseClassMustBeDerivedFromService(this); @@ -4908,7 +4657,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodGeneric(29); + ::grpc::Service::MarkMethodGeneric(27); } ~WithGenericMethod_SubscribeUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -4925,7 +4674,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodGeneric(30); + ::grpc::Service::MarkMethodGeneric(28); } ~WithGenericMethod_SubscribeDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -4942,7 +4691,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodGeneric(31); + ::grpc::Service::MarkMethodGeneric(29); } ~WithGenericMethod_SubscribeScaledPressure() override { BaseClassMustBeDerivedFromService(this); @@ -4959,7 +4708,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodGeneric(32); + ::grpc::Service::MarkMethodGeneric(30); } ~WithGenericMethod_SubscribeHeading() override { BaseClassMustBeDerivedFromService(this); @@ -4976,7 +4725,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodGeneric(33); + ::grpc::Service::MarkMethodGeneric(31); } ~WithGenericMethod_SubscribeAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -4993,7 +4742,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRatePosition() { - ::grpc::Service::MarkMethodGeneric(34); + ::grpc::Service::MarkMethodGeneric(32); } ~WithGenericMethod_SetRatePosition() override { BaseClassMustBeDerivedFromService(this); @@ -5010,7 +4759,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateHome() { - ::grpc::Service::MarkMethodGeneric(35); + ::grpc::Service::MarkMethodGeneric(33); } ~WithGenericMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); @@ -5027,7 +4776,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateInAir() { - ::grpc::Service::MarkMethodGeneric(36); + ::grpc::Service::MarkMethodGeneric(34); } ~WithGenericMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -5044,7 +4793,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodGeneric(37); + ::grpc::Service::MarkMethodGeneric(35); } ~WithGenericMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -5061,7 +4810,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodGeneric(38); + ::grpc::Service::MarkMethodGeneric(36); } ~WithGenericMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -5078,7 +4827,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodGeneric(39); + ::grpc::Service::MarkMethodGeneric(37); } ~WithGenericMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -5095,7 +4844,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodGeneric(40); + ::grpc::Service::MarkMethodGeneric(38); } ~WithGenericMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -5107,29 +4856,12 @@ class TelemetryService final { } }; template - class WithGenericMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithGenericMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodGeneric(41); - } - ~WithGenericMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - }; - template class WithGenericMethod_SetRateVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodGeneric(42); + ::grpc::Service::MarkMethodGeneric(39); } ~WithGenericMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -5146,7 +4878,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodGeneric(43); + ::grpc::Service::MarkMethodGeneric(40); } ~WithGenericMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -5163,7 +4895,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateBattery() { - ::grpc::Service::MarkMethodGeneric(44); + ::grpc::Service::MarkMethodGeneric(41); } ~WithGenericMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -5180,7 +4912,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodGeneric(45); + ::grpc::Service::MarkMethodGeneric(42); } ~WithGenericMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5197,7 +4929,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodGeneric(46); + ::grpc::Service::MarkMethodGeneric(43); } ~WithGenericMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -5214,7 +4946,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodGeneric(47); + ::grpc::Service::MarkMethodGeneric(44); } ~WithGenericMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5231,7 +4963,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodGeneric(48); + ::grpc::Service::MarkMethodGeneric(45); } ~WithGenericMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -5248,7 +4980,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodGeneric(49); + ::grpc::Service::MarkMethodGeneric(46); } ~WithGenericMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -5265,7 +4997,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodGeneric(50); + ::grpc::Service::MarkMethodGeneric(47); } ~WithGenericMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -5282,7 +5014,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodGeneric(51); + ::grpc::Service::MarkMethodGeneric(48); } ~WithGenericMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -5299,7 +5031,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateImu() { - ::grpc::Service::MarkMethodGeneric(52); + ::grpc::Service::MarkMethodGeneric(49); } ~WithGenericMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -5316,7 +5048,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodGeneric(53); + ::grpc::Service::MarkMethodGeneric(50); } ~WithGenericMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -5333,7 +5065,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodGeneric(54); + ::grpc::Service::MarkMethodGeneric(51); } ~WithGenericMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -5350,7 +5082,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodGeneric(55); + ::grpc::Service::MarkMethodGeneric(52); } ~WithGenericMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -5367,7 +5099,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodGeneric(56); + ::grpc::Service::MarkMethodGeneric(53); } ~WithGenericMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -5384,7 +5116,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodGeneric(57); + ::grpc::Service::MarkMethodGeneric(54); } ~WithGenericMethod_SetRateAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -5401,7 +5133,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodGeneric(58); + ::grpc::Service::MarkMethodGeneric(55); } ~WithGenericMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -5593,52 +5325,12 @@ class TelemetryService final { } }; template - class WithRawMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodRaw(9); - } - ~WithRawMethod_SubscribeCameraAttitudeQuaternion() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SubscribeCameraAttitudeEuler : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodRaw(10); - } - ~WithRawMethod_SubscribeCameraAttitudeEuler() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSubscribeCameraAttitudeEuler(::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); - } - }; - template class WithRawMethod_SubscribeVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodRaw(11); + ::grpc::Service::MarkMethodRaw(9); } ~WithRawMethod_SubscribeVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -5649,7 +5341,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeVelocityNed(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5658,7 +5350,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodRaw(12); + ::grpc::Service::MarkMethodRaw(10); } ~WithRawMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -5669,7 +5361,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGpsInfo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5678,7 +5370,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodRaw(13); + ::grpc::Service::MarkMethodRaw(11); } ~WithRawMethod_SubscribeRawGps() override { BaseClassMustBeDerivedFromService(this); @@ -5689,7 +5381,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRawGps(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5698,7 +5390,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodRaw(14); + ::grpc::Service::MarkMethodRaw(12); } ~WithRawMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -5709,7 +5401,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeBattery(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5718,7 +5410,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodRaw(15); + ::grpc::Service::MarkMethodRaw(13); } ~WithRawMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -5729,7 +5421,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFlightMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5738,7 +5430,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodRaw(16); + ::grpc::Service::MarkMethodRaw(14); } ~WithRawMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -5749,7 +5441,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealth(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5758,7 +5450,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodRaw(17); + ::grpc::Service::MarkMethodRaw(15); } ~WithRawMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5769,7 +5461,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRcStatus(::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(17, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5778,7 +5470,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodRaw(18); + ::grpc::Service::MarkMethodRaw(16); } ~WithRawMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -5789,7 +5481,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatusText(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5798,7 +5490,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodRaw(19); + ::grpc::Service::MarkMethodRaw(17); } ~WithRawMethod_SubscribeActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -5809,7 +5501,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeActuatorControlTarget(::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(19, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5818,7 +5510,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodRaw(20); + ::grpc::Service::MarkMethodRaw(18); } ~WithRawMethod_SubscribeActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5829,7 +5521,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeActuatorOutputStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(18, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5838,7 +5530,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodRaw(21); + ::grpc::Service::MarkMethodRaw(19); } ~WithRawMethod_SubscribeOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -5849,7 +5541,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeOdometry(::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(21, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(19, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5858,7 +5550,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodRaw(22); + ::grpc::Service::MarkMethodRaw(20); } ~WithRawMethod_SubscribePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -5869,7 +5561,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribePositionVelocityNed(::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(22, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(20, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5878,7 +5570,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodRaw(23); + ::grpc::Service::MarkMethodRaw(21); } ~WithRawMethod_SubscribeGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -5889,7 +5581,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGroundTruth(::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(23, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(21, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5898,7 +5590,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodRaw(24); + ::grpc::Service::MarkMethodRaw(22); } ~WithRawMethod_SubscribeFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -5909,7 +5601,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFixedwingMetrics(::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(24, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(22, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5918,7 +5610,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeImu() { - ::grpc::Service::MarkMethodRaw(25); + ::grpc::Service::MarkMethodRaw(23); } ~WithRawMethod_SubscribeImu() override { BaseClassMustBeDerivedFromService(this); @@ -5929,7 +5621,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeImu(::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(25, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(23, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5938,7 +5630,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodRaw(26); + ::grpc::Service::MarkMethodRaw(24); } ~WithRawMethod_SubscribeScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -5949,7 +5641,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeScaledImu(::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(26, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(24, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5958,7 +5650,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodRaw(27); + ::grpc::Service::MarkMethodRaw(25); } ~WithRawMethod_SubscribeRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -5969,7 +5661,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRawImu(::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(27, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(25, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5978,7 +5670,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodRaw(28); + ::grpc::Service::MarkMethodRaw(26); } ~WithRawMethod_SubscribeHealthAllOk() override { BaseClassMustBeDerivedFromService(this); @@ -5989,7 +5681,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealthAllOk(::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(28, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(26, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -5998,7 +5690,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodRaw(29); + ::grpc::Service::MarkMethodRaw(27); } ~WithRawMethod_SubscribeUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -6009,7 +5701,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeUnixEpochTime(::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(29, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(27, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -6018,7 +5710,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodRaw(30); + ::grpc::Service::MarkMethodRaw(28); } ~WithRawMethod_SubscribeDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -6029,7 +5721,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeDistanceSensor(::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(30, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(28, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -6038,7 +5730,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodRaw(31); + ::grpc::Service::MarkMethodRaw(29); } ~WithRawMethod_SubscribeScaledPressure() override { BaseClassMustBeDerivedFromService(this); @@ -6049,7 +5741,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeScaledPressure(::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(31, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(29, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -6058,7 +5750,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodRaw(32); + ::grpc::Service::MarkMethodRaw(30); } ~WithRawMethod_SubscribeHeading() override { BaseClassMustBeDerivedFromService(this); @@ -6069,7 +5761,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHeading(::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(32, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(30, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -6078,7 +5770,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodRaw(33); + ::grpc::Service::MarkMethodRaw(31); } ~WithRawMethod_SubscribeAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -6089,7 +5781,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeAltitude(::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(33, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(31, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -6098,7 +5790,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRatePosition() { - ::grpc::Service::MarkMethodRaw(34); + ::grpc::Service::MarkMethodRaw(32); } ~WithRawMethod_SetRatePosition() override { BaseClassMustBeDerivedFromService(this); @@ -6109,7 +5801,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRatePosition(::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(34, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(32, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6118,7 +5810,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateHome() { - ::grpc::Service::MarkMethodRaw(35); + ::grpc::Service::MarkMethodRaw(33); } ~WithRawMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); @@ -6129,7 +5821,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateHome(::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(35, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(33, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6138,7 +5830,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateInAir() { - ::grpc::Service::MarkMethodRaw(36); + ::grpc::Service::MarkMethodRaw(34); } ~WithRawMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -6149,7 +5841,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateInAir(::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(36, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6158,7 +5850,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodRaw(37); + ::grpc::Service::MarkMethodRaw(35); } ~WithRawMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -6169,7 +5861,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateLandedState(::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(37, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6178,7 +5870,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodRaw(38); + ::grpc::Service::MarkMethodRaw(36); } ~WithRawMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -6189,7 +5881,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateVtolState(::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(38, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(36, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6198,7 +5890,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodRaw(39); + ::grpc::Service::MarkMethodRaw(37); } ~WithRawMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -6209,7 +5901,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAttitudeQuaternion(::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(39, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(37, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6218,7 +5910,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodRaw(40); + ::grpc::Service::MarkMethodRaw(38); } ~WithRawMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -6229,27 +5921,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAttitudeEuler(::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(40, context, request, response, new_call_cq, notification_cq, tag); - } - }; - template - class WithRawMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodRaw(41); - } - ~WithRawMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - void RequestSetRateCameraAttitude(::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(41, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(38, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6258,7 +5930,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodRaw(42); + ::grpc::Service::MarkMethodRaw(39); } ~WithRawMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -6269,7 +5941,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateVelocityNed(::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(42, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(39, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6278,7 +5950,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodRaw(43); + ::grpc::Service::MarkMethodRaw(40); } ~WithRawMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -6289,7 +5961,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateGpsInfo(::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(43, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(40, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6298,7 +5970,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateBattery() { - ::grpc::Service::MarkMethodRaw(44); + ::grpc::Service::MarkMethodRaw(41); } ~WithRawMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -6309,7 +5981,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateBattery(::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(44, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(41, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6318,7 +5990,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodRaw(45); + ::grpc::Service::MarkMethodRaw(42); } ~WithRawMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -6329,7 +6001,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateRcStatus(::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(45, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(42, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6338,7 +6010,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodRaw(46); + ::grpc::Service::MarkMethodRaw(43); } ~WithRawMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -6349,7 +6021,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateActuatorControlTarget(::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(46, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(43, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6358,7 +6030,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodRaw(47); + ::grpc::Service::MarkMethodRaw(44); } ~WithRawMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -6369,7 +6041,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateActuatorOutputStatus(::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(47, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(44, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6378,7 +6050,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodRaw(48); + ::grpc::Service::MarkMethodRaw(45); } ~WithRawMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -6389,7 +6061,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateOdometry(::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(48, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(45, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6398,7 +6070,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodRaw(49); + ::grpc::Service::MarkMethodRaw(46); } ~WithRawMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -6409,7 +6081,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRatePositionVelocityNed(::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(49, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(46, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6418,7 +6090,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodRaw(50); + ::grpc::Service::MarkMethodRaw(47); } ~WithRawMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -6429,7 +6101,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateGroundTruth(::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(50, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(47, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6438,7 +6110,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodRaw(51); + ::grpc::Service::MarkMethodRaw(48); } ~WithRawMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -6449,7 +6121,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateFixedwingMetrics(::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(51, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(48, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6458,7 +6130,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateImu() { - ::grpc::Service::MarkMethodRaw(52); + ::grpc::Service::MarkMethodRaw(49); } ~WithRawMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -6469,7 +6141,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateImu(::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(52, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(49, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6478,7 +6150,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodRaw(53); + ::grpc::Service::MarkMethodRaw(50); } ~WithRawMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -6489,7 +6161,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateScaledImu(::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(53, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(50, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6498,7 +6170,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodRaw(54); + ::grpc::Service::MarkMethodRaw(51); } ~WithRawMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -6509,7 +6181,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateRawImu(::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(54, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(51, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6518,7 +6190,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodRaw(55); + ::grpc::Service::MarkMethodRaw(52); } ~WithRawMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -6529,7 +6201,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateUnixEpochTime(::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(55, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(52, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6538,7 +6210,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodRaw(56); + ::grpc::Service::MarkMethodRaw(53); } ~WithRawMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -6549,7 +6221,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateDistanceSensor(::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(56, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(53, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6558,7 +6230,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodRaw(57); + ::grpc::Service::MarkMethodRaw(54); } ~WithRawMethod_SetRateAltitude() override { BaseClassMustBeDerivedFromService(this); @@ -6569,7 +6241,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSetRateAltitude(::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(57, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(54, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6578,7 +6250,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodRaw(58); + ::grpc::Service::MarkMethodRaw(55); } ~WithRawMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -6589,7 +6261,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestGetGpsGlobalOrigin(::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(58, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(55, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6787,51 +6459,7 @@ class TelemetryService final { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeAttitudeAngularVelocityBody( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template - class WithRawCallbackMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodRawCallback(9, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCameraAttitudeQuaternion(context, request); })); - } - ~WithRawCallbackMethod_SubscribeCameraAttitudeQuaternion() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCameraAttitudeQuaternion( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } - }; - template - class WithRawCallbackMethod_SubscribeCameraAttitudeEuler : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodRawCallback(10, - new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeCameraAttitudeEuler(context, request); })); - } - ~WithRawCallbackMethod_SubscribeCameraAttitudeEuler() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeCameraAttitudeEuler( + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeAttitudeAngularVelocityBody( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template @@ -6840,7 +6468,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(11, + ::grpc::Service::MarkMethodRawCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeVelocityNed(context, request); })); @@ -6862,7 +6490,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodRawCallback(12, + ::grpc::Service::MarkMethodRawCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeGpsInfo(context, request); })); @@ -6884,7 +6512,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodRawCallback(13, + ::grpc::Service::MarkMethodRawCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeRawGps(context, request); })); @@ -6906,7 +6534,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodRawCallback(14, + ::grpc::Service::MarkMethodRawCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeBattery(context, request); })); @@ -6928,7 +6556,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodRawCallback(15, + ::grpc::Service::MarkMethodRawCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFlightMode(context, request); })); @@ -6950,7 +6578,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodRawCallback(16, + ::grpc::Service::MarkMethodRawCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeHealth(context, request); })); @@ -6972,7 +6600,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodRawCallback(17, + ::grpc::Service::MarkMethodRawCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeRcStatus(context, request); })); @@ -6994,7 +6622,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodRawCallback(18, + ::grpc::Service::MarkMethodRawCallback(16, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeStatusText(context, request); })); @@ -7016,7 +6644,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodRawCallback(19, + ::grpc::Service::MarkMethodRawCallback(17, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeActuatorControlTarget(context, request); })); @@ -7038,7 +6666,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodRawCallback(20, + ::grpc::Service::MarkMethodRawCallback(18, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeActuatorOutputStatus(context, request); })); @@ -7060,7 +6688,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodRawCallback(21, + ::grpc::Service::MarkMethodRawCallback(19, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeOdometry(context, request); })); @@ -7082,7 +6710,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(22, + ::grpc::Service::MarkMethodRawCallback(20, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribePositionVelocityNed(context, request); })); @@ -7104,7 +6732,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodRawCallback(23, + ::grpc::Service::MarkMethodRawCallback(21, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeGroundTruth(context, request); })); @@ -7126,7 +6754,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodRawCallback(24, + ::grpc::Service::MarkMethodRawCallback(22, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeFixedwingMetrics(context, request); })); @@ -7148,7 +6776,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeImu() { - ::grpc::Service::MarkMethodRawCallback(25, + ::grpc::Service::MarkMethodRawCallback(23, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeImu(context, request); })); @@ -7170,7 +6798,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodRawCallback(26, + ::grpc::Service::MarkMethodRawCallback(24, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeScaledImu(context, request); })); @@ -7192,7 +6820,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodRawCallback(27, + ::grpc::Service::MarkMethodRawCallback(25, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeRawImu(context, request); })); @@ -7214,7 +6842,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodRawCallback(28, + ::grpc::Service::MarkMethodRawCallback(26, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeHealthAllOk(context, request); })); @@ -7236,7 +6864,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodRawCallback(29, + ::grpc::Service::MarkMethodRawCallback(27, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeUnixEpochTime(context, request); })); @@ -7258,7 +6886,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodRawCallback(30, + ::grpc::Service::MarkMethodRawCallback(28, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeDistanceSensor(context, request); })); @@ -7280,7 +6908,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodRawCallback(31, + ::grpc::Service::MarkMethodRawCallback(29, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeScaledPressure(context, request); })); @@ -7302,7 +6930,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodRawCallback(32, + ::grpc::Service::MarkMethodRawCallback(30, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeHeading(context, request); })); @@ -7324,7 +6952,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodRawCallback(33, + ::grpc::Service::MarkMethodRawCallback(31, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeAltitude(context, request); })); @@ -7346,7 +6974,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRatePosition() { - ::grpc::Service::MarkMethodRawCallback(34, + ::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->SetRatePosition(context, request, response); })); @@ -7368,7 +6996,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateHome() { - ::grpc::Service::MarkMethodRawCallback(35, + ::grpc::Service::MarkMethodRawCallback(33, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateHome(context, request, response); })); @@ -7390,7 +7018,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateInAir() { - ::grpc::Service::MarkMethodRawCallback(36, + ::grpc::Service::MarkMethodRawCallback(34, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateInAir(context, request, response); })); @@ -7412,7 +7040,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodRawCallback(37, + ::grpc::Service::MarkMethodRawCallback(35, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateLandedState(context, request, response); })); @@ -7434,7 +7062,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodRawCallback(38, + ::grpc::Service::MarkMethodRawCallback(36, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateVtolState(context, request, response); })); @@ -7456,7 +7084,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodRawCallback(39, + ::grpc::Service::MarkMethodRawCallback(37, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateAttitudeQuaternion(context, request, response); })); @@ -7478,7 +7106,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodRawCallback(40, + ::grpc::Service::MarkMethodRawCallback(38, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateAttitudeEuler(context, request, response); })); @@ -7495,34 +7123,12 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithRawCallbackMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodRawCallback(41, - new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( - [this]( - ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateCameraAttitude(context, request, response); })); - } - ~WithRawCallbackMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable synchronous version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - virtual ::grpc::ServerUnaryReactor* SetRateCameraAttitude( - ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } - }; - template class WithRawCallbackMethod_SetRateVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(42, + ::grpc::Service::MarkMethodRawCallback(39, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateVelocityNed(context, request, response); })); @@ -7544,7 +7150,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodRawCallback(43, + ::grpc::Service::MarkMethodRawCallback(40, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateGpsInfo(context, request, response); })); @@ -7566,7 +7172,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateBattery() { - ::grpc::Service::MarkMethodRawCallback(44, + ::grpc::Service::MarkMethodRawCallback(41, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateBattery(context, request, response); })); @@ -7588,7 +7194,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodRawCallback(45, + ::grpc::Service::MarkMethodRawCallback(42, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateRcStatus(context, request, response); })); @@ -7610,7 +7216,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodRawCallback(46, + ::grpc::Service::MarkMethodRawCallback(43, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateActuatorControlTarget(context, request, response); })); @@ -7632,7 +7238,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodRawCallback(47, + ::grpc::Service::MarkMethodRawCallback(44, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateActuatorOutputStatus(context, request, response); })); @@ -7654,7 +7260,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodRawCallback(48, + ::grpc::Service::MarkMethodRawCallback(45, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateOdometry(context, request, response); })); @@ -7676,7 +7282,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(49, + ::grpc::Service::MarkMethodRawCallback(46, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRatePositionVelocityNed(context, request, response); })); @@ -7698,7 +7304,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodRawCallback(50, + ::grpc::Service::MarkMethodRawCallback(47, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateGroundTruth(context, request, response); })); @@ -7720,7 +7326,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodRawCallback(51, + ::grpc::Service::MarkMethodRawCallback(48, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateFixedwingMetrics(context, request, response); })); @@ -7742,7 +7348,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateImu() { - ::grpc::Service::MarkMethodRawCallback(52, + ::grpc::Service::MarkMethodRawCallback(49, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateImu(context, request, response); })); @@ -7764,7 +7370,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodRawCallback(53, + ::grpc::Service::MarkMethodRawCallback(50, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateScaledImu(context, request, response); })); @@ -7786,7 +7392,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodRawCallback(54, + ::grpc::Service::MarkMethodRawCallback(51, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateRawImu(context, request, response); })); @@ -7808,7 +7414,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodRawCallback(55, + ::grpc::Service::MarkMethodRawCallback(52, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateUnixEpochTime(context, request, response); })); @@ -7830,7 +7436,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodRawCallback(56, + ::grpc::Service::MarkMethodRawCallback(53, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateDistanceSensor(context, request, response); })); @@ -7852,7 +7458,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodRawCallback(57, + ::grpc::Service::MarkMethodRawCallback(54, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetRateAltitude(context, request, response); })); @@ -7874,7 +7480,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodRawCallback(58, + ::grpc::Service::MarkMethodRawCallback(55, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetGpsGlobalOrigin(context, request, response); })); @@ -7896,7 +7502,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRatePosition() { - ::grpc::Service::MarkMethodStreamed(34, + ::grpc::Service::MarkMethodStreamed(32, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>( [this](::grpc::ServerContext* context, @@ -7923,7 +7529,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateHome() { - ::grpc::Service::MarkMethodStreamed(35, + ::grpc::Service::MarkMethodStreamed(33, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>( [this](::grpc::ServerContext* context, @@ -7950,7 +7556,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateInAir() { - ::grpc::Service::MarkMethodStreamed(36, + ::grpc::Service::MarkMethodStreamed(34, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>( [this](::grpc::ServerContext* context, @@ -7977,7 +7583,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodStreamed(37, + ::grpc::Service::MarkMethodStreamed(35, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>( [this](::grpc::ServerContext* context, @@ -8004,7 +7610,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodStreamed(38, + ::grpc::Service::MarkMethodStreamed(36, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>( [this](::grpc::ServerContext* context, @@ -8031,7 +7637,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodStreamed(39, + ::grpc::Service::MarkMethodStreamed(37, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>( [this](::grpc::ServerContext* context, @@ -8058,7 +7664,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodStreamed(40, + ::grpc::Service::MarkMethodStreamed(38, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>( [this](::grpc::ServerContext* context, @@ -8080,39 +7686,12 @@ class TelemetryService final { virtual ::grpc::Status StreamedSetRateAttitudeEuler(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest,::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>* server_unary_streamer) = 0; }; template - class WithStreamedUnaryMethod_SetRateCameraAttitude : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithStreamedUnaryMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodStreamed(41, - new ::grpc::internal::StreamedUnaryHandler< - ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerUnaryStreamer< - ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* streamer) { - return this->StreamedSetRateCameraAttitude(context, - streamer); - })); - } - ~WithStreamedUnaryMethod_SetRateCameraAttitude() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SetRateCameraAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse* /*response*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with streamed unary - virtual ::grpc::Status StreamedSetRateCameraAttitude(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest,::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>* server_unary_streamer) = 0; - }; - template class WithStreamedUnaryMethod_SetRateVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodStreamed(42, + ::grpc::Service::MarkMethodStreamed(39, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -8139,7 +7718,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodStreamed(43, + ::grpc::Service::MarkMethodStreamed(40, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>( [this](::grpc::ServerContext* context, @@ -8166,7 +7745,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateBattery() { - ::grpc::Service::MarkMethodStreamed(44, + ::grpc::Service::MarkMethodStreamed(41, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>( [this](::grpc::ServerContext* context, @@ -8193,7 +7772,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodStreamed(45, + ::grpc::Service::MarkMethodStreamed(42, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>( [this](::grpc::ServerContext* context, @@ -8220,7 +7799,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodStreamed(46, + ::grpc::Service::MarkMethodStreamed(43, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>( [this](::grpc::ServerContext* context, @@ -8247,7 +7826,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodStreamed(47, + ::grpc::Service::MarkMethodStreamed(44, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>( [this](::grpc::ServerContext* context, @@ -8274,7 +7853,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodStreamed(48, + ::grpc::Service::MarkMethodStreamed(45, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>( [this](::grpc::ServerContext* context, @@ -8301,7 +7880,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodStreamed(49, + ::grpc::Service::MarkMethodStreamed(46, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -8328,7 +7907,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodStreamed(50, + ::grpc::Service::MarkMethodStreamed(47, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>( [this](::grpc::ServerContext* context, @@ -8355,7 +7934,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodStreamed(51, + ::grpc::Service::MarkMethodStreamed(48, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>( [this](::grpc::ServerContext* context, @@ -8382,7 +7961,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateImu() { - ::grpc::Service::MarkMethodStreamed(52, + ::grpc::Service::MarkMethodStreamed(49, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>( [this](::grpc::ServerContext* context, @@ -8409,7 +7988,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodStreamed(53, + ::grpc::Service::MarkMethodStreamed(50, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>( [this](::grpc::ServerContext* context, @@ -8436,7 +8015,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodStreamed(54, + ::grpc::Service::MarkMethodStreamed(51, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>( [this](::grpc::ServerContext* context, @@ -8463,7 +8042,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodStreamed(55, + ::grpc::Service::MarkMethodStreamed(52, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>( [this](::grpc::ServerContext* context, @@ -8490,7 +8069,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodStreamed(56, + ::grpc::Service::MarkMethodStreamed(53, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>( [this](::grpc::ServerContext* context, @@ -8517,7 +8096,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateAltitude() { - ::grpc::Service::MarkMethodStreamed(57, + ::grpc::Service::MarkMethodStreamed(54, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>( [this](::grpc::ServerContext* context, @@ -8544,7 +8123,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodStreamed(58, + ::grpc::Service::MarkMethodStreamed(55, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>( [this](::grpc::ServerContext* context, @@ -8565,7 +8144,7 @@ class TelemetryService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedGetGpsGlobalOrigin(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest,::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetRatePosition > > > > > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_SetRatePosition > > > > > > > > > > > > > > > > > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribePosition : public BaseClass { private: @@ -8810,66 +8389,12 @@ class TelemetryService final { virtual ::grpc::Status StreamedSubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest,::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* server_split_streamer) = 0; }; template - class WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodStreamed(9, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* streamer) { - return this->StreamedSubscribeCameraAttitudeQuaternion(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest,::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* server_split_streamer) = 0; - }; - template - class WithSplitStreamingMethod_SubscribeCameraAttitudeEuler : public BaseClass { - private: - void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} - public: - WithSplitStreamingMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodStreamed(10, - new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>( - [this](::grpc::ServerContext* context, - ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* streamer) { - return this->StreamedSubscribeCameraAttitudeEuler(context, - streamer); - })); - } - ~WithSplitStreamingMethod_SubscribeCameraAttitudeEuler() override { - BaseClassMustBeDerivedFromService(this); - } - // disable regular version of this method - ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* /*writer*/) override { - abort(); - return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); - } - // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeCameraAttitudeEuler(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest,::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* server_split_streamer) = 0; - }; - template class WithSplitStreamingMethod_SubscribeVelocityNed : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeVelocityNed() { - ::grpc::Service::MarkMethodStreamed(11, + ::grpc::Service::MarkMethodStreamed(9, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest, ::mavsdk::rpc::telemetry::VelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -8896,7 +8421,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodStreamed(12, + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( [this](::grpc::ServerContext* context, @@ -8923,7 +8448,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeRawGps() { - ::grpc::Service::MarkMethodStreamed(13, + ::grpc::Service::MarkMethodStreamed(11, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRawGpsRequest, ::mavsdk::rpc::telemetry::RawGpsResponse>( [this](::grpc::ServerContext* context, @@ -8950,7 +8475,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodStreamed(14, + ::grpc::Service::MarkMethodStreamed(12, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>( [this](::grpc::ServerContext* context, @@ -8977,7 +8502,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodStreamed(15, + ::grpc::Service::MarkMethodStreamed(13, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>( [this](::grpc::ServerContext* context, @@ -9004,7 +8529,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodStreamed(16, + ::grpc::Service::MarkMethodStreamed(14, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>( [this](::grpc::ServerContext* context, @@ -9031,7 +8556,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodStreamed(17, + ::grpc::Service::MarkMethodStreamed(15, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>( [this](::grpc::ServerContext* context, @@ -9058,7 +8583,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodStreamed(18, + ::grpc::Service::MarkMethodStreamed(16, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>( [this](::grpc::ServerContext* context, @@ -9085,7 +8610,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeActuatorControlTarget() { - ::grpc::Service::MarkMethodStreamed(19, + ::grpc::Service::MarkMethodStreamed(17, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>( [this](::grpc::ServerContext* context, @@ -9112,7 +8637,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeActuatorOutputStatus() { - ::grpc::Service::MarkMethodStreamed(20, + ::grpc::Service::MarkMethodStreamed(18, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>( [this](::grpc::ServerContext* context, @@ -9139,7 +8664,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeOdometry() { - ::grpc::Service::MarkMethodStreamed(21, + ::grpc::Service::MarkMethodStreamed(19, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeOdometryRequest, ::mavsdk::rpc::telemetry::OdometryResponse>( [this](::grpc::ServerContext* context, @@ -9166,7 +8691,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribePositionVelocityNed() { - ::grpc::Service::MarkMethodStreamed(22, + ::grpc::Service::MarkMethodStreamed(20, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::PositionVelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -9193,7 +8718,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeGroundTruth() { - ::grpc::Service::MarkMethodStreamed(23, + ::grpc::Service::MarkMethodStreamed(21, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest, ::mavsdk::rpc::telemetry::GroundTruthResponse>( [this](::grpc::ServerContext* context, @@ -9220,7 +8745,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeFixedwingMetrics() { - ::grpc::Service::MarkMethodStreamed(24, + ::grpc::Service::MarkMethodStreamed(22, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::FixedwingMetricsResponse>( [this](::grpc::ServerContext* context, @@ -9247,7 +8772,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeImu() { - ::grpc::Service::MarkMethodStreamed(25, + ::grpc::Service::MarkMethodStreamed(23, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeImuRequest, ::mavsdk::rpc::telemetry::ImuResponse>( [this](::grpc::ServerContext* context, @@ -9274,7 +8799,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeScaledImu() { - ::grpc::Service::MarkMethodStreamed(26, + ::grpc::Service::MarkMethodStreamed(24, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeScaledImuRequest, ::mavsdk::rpc::telemetry::ScaledImuResponse>( [this](::grpc::ServerContext* context, @@ -9301,7 +8826,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeRawImu() { - ::grpc::Service::MarkMethodStreamed(27, + ::grpc::Service::MarkMethodStreamed(25, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRawImuRequest, ::mavsdk::rpc::telemetry::RawImuResponse>( [this](::grpc::ServerContext* context, @@ -9328,7 +8853,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeHealthAllOk() { - ::grpc::Service::MarkMethodStreamed(28, + ::grpc::Service::MarkMethodStreamed(26, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest, ::mavsdk::rpc::telemetry::HealthAllOkResponse>( [this](::grpc::ServerContext* context, @@ -9355,7 +8880,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeUnixEpochTime() { - ::grpc::Service::MarkMethodStreamed(29, + ::grpc::Service::MarkMethodStreamed(27, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::UnixEpochTimeResponse>( [this](::grpc::ServerContext* context, @@ -9382,7 +8907,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeDistanceSensor() { - ::grpc::Service::MarkMethodStreamed(30, + ::grpc::Service::MarkMethodStreamed(28, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest, ::mavsdk::rpc::telemetry::DistanceSensorResponse>( [this](::grpc::ServerContext* context, @@ -9409,7 +8934,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeScaledPressure() { - ::grpc::Service::MarkMethodStreamed(31, + ::grpc::Service::MarkMethodStreamed(29, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest, ::mavsdk::rpc::telemetry::ScaledPressureResponse>( [this](::grpc::ServerContext* context, @@ -9436,7 +8961,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeHeading() { - ::grpc::Service::MarkMethodStreamed(32, + ::grpc::Service::MarkMethodStreamed(30, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHeadingRequest, ::mavsdk::rpc::telemetry::HeadingResponse>( [this](::grpc::ServerContext* context, @@ -9463,7 +8988,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeAltitude() { - ::grpc::Service::MarkMethodStreamed(33, + ::grpc::Service::MarkMethodStreamed(31, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>( [this](::grpc::ServerContext* context, @@ -9484,8 +9009,8 @@ class TelemetryService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeAltitude(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest,::mavsdk::rpc::telemetry::AltitudeResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > SplitStreamedService; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > StreamedService; + typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > SplitStreamedService; + typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace telemetry diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc index d0e17f6a56..213df88266 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc @@ -414,30 +414,6 @@ struct SubscribeDistanceSensorRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeDistanceSensorRequestDefaultTypeInternal _SubscribeDistanceSensorRequest_default_instance_; template -PROTOBUF_CONSTEXPR SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest(::_pbi::ConstantInitialized) {} -struct SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal() {} - union { - SubscribeCameraAttitudeQuaternionRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal _SubscribeCameraAttitudeQuaternionRequest_default_instance_; - template -PROTOBUF_CONSTEXPR SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest(::_pbi::ConstantInitialized) {} -struct SubscribeCameraAttitudeEulerRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeCameraAttitudeEulerRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeCameraAttitudeEulerRequestDefaultTypeInternal() {} - union { - SubscribeCameraAttitudeEulerRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeCameraAttitudeEulerRequestDefaultTypeInternal _SubscribeCameraAttitudeEulerRequest_default_instance_; - template PROTOBUF_CONSTEXPR SubscribeBatteryRequest::SubscribeBatteryRequest(::_pbi::ConstantInitialized) {} struct SubscribeBatteryRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR SubscribeBatteryRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} @@ -898,44 +874,6 @@ struct SetRateDistanceSensorRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateDistanceSensorRequestDefaultTypeInternal _SetRateDistanceSensorRequest_default_instance_; -inline constexpr SetRateCameraAttitudeRequest::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : rate_hz_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR SetRateCameraAttitudeRequest::SetRateCameraAttitudeRequest(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct SetRateCameraAttitudeRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRateCameraAttitudeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRateCameraAttitudeRequestDefaultTypeInternal() {} - union { - SetRateCameraAttitudeRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateCameraAttitudeRequestDefaultTypeInternal _SetRateCameraAttitudeRequest_default_instance_; - -inline constexpr SetRateCameraAttitudeQuaternionRequest::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : rate_hz_{0}, - _cached_size_{0} {} - -template -PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionRequest::SetRateCameraAttitudeQuaternionRequest(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal() {} - union { - SetRateCameraAttitudeQuaternionRequest _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal _SetRateCameraAttitudeQuaternionRequest_default_instance_; - inline constexpr SetRateBatteryRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : rate_hz_{0}, @@ -2040,44 +1978,6 @@ struct SetRateDistanceSensorResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateDistanceSensorResponseDefaultTypeInternal _SetRateDistanceSensorResponse_default_instance_; -inline constexpr SetRateCameraAttitudeResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - telemetry_result_{nullptr} {} - -template -PROTOBUF_CONSTEXPR SetRateCameraAttitudeResponse::SetRateCameraAttitudeResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct SetRateCameraAttitudeResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRateCameraAttitudeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRateCameraAttitudeResponseDefaultTypeInternal() {} - union { - SetRateCameraAttitudeResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateCameraAttitudeResponseDefaultTypeInternal _SetRateCameraAttitudeResponse_default_instance_; - -inline constexpr SetRateCameraAttitudeQuaternionResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - telemetry_result_{nullptr} {} - -template -PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionResponse::SetRateCameraAttitudeQuaternionResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal() {} - union { - SetRateCameraAttitudeQuaternionResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal _SetRateCameraAttitudeQuaternionResponse_default_instance_; - inline constexpr SetRateBatteryResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -2513,44 +2413,6 @@ struct DistanceSensorDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 DistanceSensorDefaultTypeInternal _DistanceSensor_default_instance_; -inline constexpr CameraAttitudeQuaternionResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - attitude_quaternion_{nullptr} {} - -template -PROTOBUF_CONSTEXPR CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct CameraAttitudeQuaternionResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR CameraAttitudeQuaternionResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~CameraAttitudeQuaternionResponseDefaultTypeInternal() {} - union { - CameraAttitudeQuaternionResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraAttitudeQuaternionResponseDefaultTypeInternal _CameraAttitudeQuaternionResponse_default_instance_; - -inline constexpr CameraAttitudeEulerResponse::Impl_::Impl_( - ::_pbi::ConstantInitialized) noexcept - : _cached_size_{0}, - attitude_euler_{nullptr} {} - -template -PROTOBUF_CONSTEXPR CameraAttitudeEulerResponse::CameraAttitudeEulerResponse(::_pbi::ConstantInitialized) - : _impl_(::_pbi::ConstantInitialized()) {} -struct CameraAttitudeEulerResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR CameraAttitudeEulerResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~CameraAttitudeEulerResponseDefaultTypeInternal() {} - union { - CameraAttitudeEulerResponse _instance; - }; -}; - -PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CameraAttitudeEulerResponseDefaultTypeInternal _CameraAttitudeEulerResponse_default_instance_; - inline constexpr BatteryResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -2800,7 +2662,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace telemetry } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[154]; +static ::_pb::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[146]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_telemetry_2ftelemetry_2eproto[7]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_telemetry_2ftelemetry_2eproto = nullptr; @@ -2965,42 +2827,6 @@ const ::uint32_t TableStruct_telemetry_2ftelemetry_2eproto::offsets[] PROTOBUF_S PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse, _impl_.attitude_angular_velocity_body_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, _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::telemetry::CameraAttitudeQuaternionResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse, _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::telemetry::CameraAttitudeQuaternionResponse, _impl_.attitude_quaternion_), - 0, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, _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::telemetry::CameraAttitudeEulerResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse, _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::telemetry::CameraAttitudeEulerResponse, _impl_.attitude_euler_), - 0, - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -3564,44 +3390,6 @@ const ::uint32_t TableStruct_telemetry_2ftelemetry_2eproto::offsets[] PROTOBUF_S PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse, _impl_.telemetry_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionRequest, _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::telemetry::SetRateCameraAttitudeQuaternionRequest, _impl_.rate_hz_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionResponse, _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::telemetry::SetRateCameraAttitudeQuaternionResponse, _impl_.telemetry_result_), - 0, - ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, _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::telemetry::SetRateCameraAttitudeRequest, _impl_.rate_hz_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse, _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::telemetry::SetRateCameraAttitudeResponse, _impl_.telemetry_result_), - 0, - ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -4343,142 +4131,134 @@ static const ::_pbi::MigrationSchema {130, 139, -1, sizeof(::mavsdk::rpc::telemetry::AttitudeEulerResponse)}, {140, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest)}, {148, 157, -1, sizeof(::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse)}, - {158, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest)}, - {166, 175, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse)}, - {176, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest)}, - {184, 193, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse)}, - {194, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest)}, - {202, 211, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNedResponse)}, - {212, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest)}, - {220, 229, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfoResponse)}, - {230, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRawGpsRequest)}, - {238, 247, -1, sizeof(::mavsdk::rpc::telemetry::RawGpsResponse)}, - {248, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeBatteryRequest)}, - {256, 265, -1, sizeof(::mavsdk::rpc::telemetry::BatteryResponse)}, - {266, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFlightModeRequest)}, - {274, -1, -1, sizeof(::mavsdk::rpc::telemetry::FlightModeResponse)}, - {283, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthRequest)}, - {291, 300, -1, sizeof(::mavsdk::rpc::telemetry::HealthResponse)}, - {301, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRcStatusRequest)}, - {309, 318, -1, sizeof(::mavsdk::rpc::telemetry::RcStatusResponse)}, - {319, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeStatusTextRequest)}, - {327, 336, -1, sizeof(::mavsdk::rpc::telemetry::StatusTextResponse)}, - {337, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest)}, - {345, 354, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTargetResponse)}, - {355, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest)}, - {363, 372, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse)}, - {373, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeOdometryRequest)}, - {381, 390, -1, sizeof(::mavsdk::rpc::telemetry::OdometryResponse)}, - {391, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest)}, - {399, 408, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNedResponse)}, - {409, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest)}, - {417, 426, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruthResponse)}, - {427, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest)}, - {435, 444, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetricsResponse)}, - {445, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeImuRequest)}, - {453, 462, -1, sizeof(::mavsdk::rpc::telemetry::ImuResponse)}, - {463, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeScaledImuRequest)}, - {471, 480, -1, sizeof(::mavsdk::rpc::telemetry::ScaledImuResponse)}, - {481, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRawImuRequest)}, - {489, 498, -1, sizeof(::mavsdk::rpc::telemetry::RawImuResponse)}, - {499, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest)}, - {507, -1, -1, sizeof(::mavsdk::rpc::telemetry::HealthAllOkResponse)}, - {516, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest)}, - {524, -1, -1, sizeof(::mavsdk::rpc::telemetry::UnixEpochTimeResponse)}, - {533, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest)}, - {541, 550, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensorResponse)}, - {551, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest)}, - {559, 568, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressureResponse)}, - {569, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHeadingRequest)}, - {577, 586, -1, sizeof(::mavsdk::rpc::telemetry::HeadingResponse)}, - {587, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAltitudeRequest)}, - {595, 604, -1, sizeof(::mavsdk::rpc::telemetry::AltitudeResponse)}, - {605, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionRequest)}, - {614, 623, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionResponse)}, - {624, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeRequest)}, - {633, 642, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeResponse)}, - {643, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirRequest)}, - {652, 661, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirResponse)}, - {662, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateRequest)}, - {671, 680, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateResponse)}, - {681, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateRequest)}, - {690, 699, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateResponse)}, - {700, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest)}, - {709, 718, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse)}, - {719, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest)}, - {728, 737, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse)}, - {738, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest)}, - {747, 756, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse)}, - {757, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionRequest)}, - {766, 775, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionResponse)}, - {776, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest)}, - {785, 794, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse)}, - {795, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedRequest)}, - {804, 813, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedResponse)}, - {814, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoRequest)}, - {823, 832, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoResponse)}, - {833, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawGpsRequest)}, - {842, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryRequest)}, - {851, 860, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryResponse)}, - {861, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusRequest)}, - {870, 879, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusResponse)}, - {880, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest)}, - {889, 898, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse)}, - {899, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest)}, - {908, 917, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse)}, - {918, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryRequest)}, - {927, 936, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryResponse)}, - {937, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest)}, - {946, 955, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse)}, - {956, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthRequest)}, - {965, 974, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthResponse)}, - {975, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest)}, - {984, 993, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse)}, - {994, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuRequest)}, - {1003, 1012, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuResponse)}, - {1013, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuRequest)}, - {1022, 1031, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuResponse)}, - {1032, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuRequest)}, - {1041, 1050, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuResponse)}, - {1051, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest)}, - {1060, 1069, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse)}, - {1070, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest)}, - {1079, 1088, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse)}, - {1089, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest)}, - {1097, 1107, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse)}, - {1109, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeRequest)}, - {1118, 1127, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeResponse)}, - {1128, -1, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, - {1140, -1, -1, sizeof(::mavsdk::rpc::telemetry::Heading)}, - {1149, -1, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, - {1162, -1, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, - {1174, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityBody)}, - {1185, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, - {1195, -1, -1, sizeof(::mavsdk::rpc::telemetry::RawGps)}, - {1217, -1, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, - {1231, -1, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, - {1246, -1, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, - {1257, -1, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, - {1267, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTarget)}, - {1277, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatus)}, - {1287, -1, -1, sizeof(::mavsdk::rpc::telemetry::Covariance)}, - {1296, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityBody)}, - {1307, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionBody)}, - {1318, 1335, -1, sizeof(::mavsdk::rpc::telemetry::Odometry)}, - {1344, 1356, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensor)}, - {1360, -1, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressure)}, - {1373, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionNed)}, - {1384, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNed)}, - {1395, 1405, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNed)}, - {1407, -1, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruth)}, - {1418, -1, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetrics)}, - {1429, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, - {1440, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, - {1451, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, - {1462, 1475, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, - {1480, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, - {1491, -1, -1, sizeof(::mavsdk::rpc::telemetry::Altitude)}, - {1505, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, + {158, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeVelocityNedRequest)}, + {166, 175, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNedResponse)}, + {176, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest)}, + {184, 193, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfoResponse)}, + {194, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRawGpsRequest)}, + {202, 211, -1, sizeof(::mavsdk::rpc::telemetry::RawGpsResponse)}, + {212, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeBatteryRequest)}, + {220, 229, -1, sizeof(::mavsdk::rpc::telemetry::BatteryResponse)}, + {230, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFlightModeRequest)}, + {238, -1, -1, sizeof(::mavsdk::rpc::telemetry::FlightModeResponse)}, + {247, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthRequest)}, + {255, 264, -1, sizeof(::mavsdk::rpc::telemetry::HealthResponse)}, + {265, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRcStatusRequest)}, + {273, 282, -1, sizeof(::mavsdk::rpc::telemetry::RcStatusResponse)}, + {283, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeStatusTextRequest)}, + {291, 300, -1, sizeof(::mavsdk::rpc::telemetry::StatusTextResponse)}, + {301, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest)}, + {309, 318, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTargetResponse)}, + {319, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest)}, + {327, 336, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse)}, + {337, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeOdometryRequest)}, + {345, 354, -1, sizeof(::mavsdk::rpc::telemetry::OdometryResponse)}, + {355, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribePositionVelocityNedRequest)}, + {363, 372, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNedResponse)}, + {373, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGroundTruthRequest)}, + {381, 390, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruthResponse)}, + {391, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFixedwingMetricsRequest)}, + {399, 408, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetricsResponse)}, + {409, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeImuRequest)}, + {417, 426, -1, sizeof(::mavsdk::rpc::telemetry::ImuResponse)}, + {427, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeScaledImuRequest)}, + {435, 444, -1, sizeof(::mavsdk::rpc::telemetry::ScaledImuResponse)}, + {445, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRawImuRequest)}, + {453, 462, -1, sizeof(::mavsdk::rpc::telemetry::RawImuResponse)}, + {463, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthAllOkRequest)}, + {471, -1, -1, sizeof(::mavsdk::rpc::telemetry::HealthAllOkResponse)}, + {480, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeUnixEpochTimeRequest)}, + {488, -1, -1, sizeof(::mavsdk::rpc::telemetry::UnixEpochTimeResponse)}, + {497, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest)}, + {505, 514, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensorResponse)}, + {515, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest)}, + {523, 532, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressureResponse)}, + {533, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHeadingRequest)}, + {541, 550, -1, sizeof(::mavsdk::rpc::telemetry::HeadingResponse)}, + {551, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAltitudeRequest)}, + {559, 568, -1, sizeof(::mavsdk::rpc::telemetry::AltitudeResponse)}, + {569, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionRequest)}, + {578, 587, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionResponse)}, + {588, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeRequest)}, + {597, 606, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeResponse)}, + {607, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirRequest)}, + {616, 625, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirResponse)}, + {626, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateRequest)}, + {635, 644, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateResponse)}, + {645, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateRequest)}, + {654, 663, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateResponse)}, + {664, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest)}, + {673, 682, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse)}, + {683, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest)}, + {692, 701, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse)}, + {702, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest)}, + {711, 720, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse)}, + {721, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedRequest)}, + {730, 739, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedResponse)}, + {740, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoRequest)}, + {749, 758, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoResponse)}, + {759, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawGpsRequest)}, + {768, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryRequest)}, + {777, 786, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryResponse)}, + {787, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusRequest)}, + {796, 805, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusResponse)}, + {806, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest)}, + {815, 824, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse)}, + {825, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest)}, + {834, 843, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse)}, + {844, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryRequest)}, + {853, 862, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryResponse)}, + {863, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest)}, + {872, 881, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse)}, + {882, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthRequest)}, + {891, 900, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthResponse)}, + {901, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest)}, + {910, 919, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse)}, + {920, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuRequest)}, + {929, 938, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuResponse)}, + {939, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuRequest)}, + {948, 957, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuResponse)}, + {958, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuRequest)}, + {967, 976, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuResponse)}, + {977, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest)}, + {986, 995, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse)}, + {996, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest)}, + {1005, 1014, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse)}, + {1015, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest)}, + {1023, 1033, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse)}, + {1035, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeRequest)}, + {1044, 1053, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeResponse)}, + {1054, -1, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, + {1066, -1, -1, sizeof(::mavsdk::rpc::telemetry::Heading)}, + {1075, -1, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, + {1088, -1, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, + {1100, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityBody)}, + {1111, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, + {1121, -1, -1, sizeof(::mavsdk::rpc::telemetry::RawGps)}, + {1143, -1, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, + {1157, -1, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, + {1172, -1, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, + {1183, -1, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, + {1193, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTarget)}, + {1203, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatus)}, + {1213, -1, -1, sizeof(::mavsdk::rpc::telemetry::Covariance)}, + {1222, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityBody)}, + {1233, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionBody)}, + {1244, 1261, -1, sizeof(::mavsdk::rpc::telemetry::Odometry)}, + {1270, 1282, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensor)}, + {1286, -1, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressure)}, + {1299, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionNed)}, + {1310, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNed)}, + {1321, 1331, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNed)}, + {1333, -1, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruth)}, + {1344, -1, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetrics)}, + {1355, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, + {1366, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, + {1377, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, + {1388, 1401, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, + {1406, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, + {1417, -1, -1, sizeof(::mavsdk::rpc::telemetry::Altitude)}, + {1431, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -4500,10 +4280,6 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_AttitudeEulerResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_AttitudeAngularVelocityBodyResponse_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SubscribeCameraAttitudeQuaternionRequest_default_instance_._instance, - &::mavsdk::rpc::telemetry::_CameraAttitudeQuaternionResponse_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SubscribeCameraAttitudeEulerRequest_default_instance_._instance, - &::mavsdk::rpc::telemetry::_CameraAttitudeEulerResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SubscribeVelocityNedRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_VelocityNedResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SubscribeGpsInfoRequest_default_instance_._instance, @@ -4566,10 +4342,6 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_SetRateAttitudeQuaternionResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateAttitudeAngularVelocityBodyRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateAttitudeAngularVelocityBodyResponse_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SetRateCameraAttitudeQuaternionRequest_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SetRateCameraAttitudeQuaternionResponse_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SetRateCameraAttitudeRequest_default_instance_._instance, - &::mavsdk::rpc::telemetry::_SetRateCameraAttitudeResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateVelocityNedRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateVelocityNedResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateGpsInfoRequest_default_instance_._instance, @@ -4663,503 +4435,477 @@ const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] PROTOBUF_SE "uest\"x\n#AttitudeAngularVelocityBodyRespo" "nse\022Q\n\036attitude_angular_velocity_body\030\001 " "\001(\0132).mavsdk.rpc.telemetry.AngularVeloci" - "tyBody\"*\n(SubscribeCameraAttitudeQuatern" - "ionRequest\"a\n CameraAttitudeQuaternionRe" - "sponse\022=\n\023attitude_quaternion\030\001 \001(\0132 .ma" - "vsdk.rpc.telemetry.Quaternion\"%\n#Subscri" - "beCameraAttitudeEulerRequest\"W\n\033CameraAt" - "titudeEulerResponse\0228\n\016attitude_euler\030\001 " - "\001(\0132 .mavsdk.rpc.telemetry.EulerAngle\"\035\n" - "\033SubscribeVelocityNedRequest\"N\n\023Velocity" - "NedResponse\0227\n\014velocity_ned\030\001 \001(\0132!.mavs" - "dk.rpc.telemetry.VelocityNed\"\031\n\027Subscrib" - "eGpsInfoRequest\"B\n\017GpsInfoResponse\022/\n\010gp" - "s_info\030\001 \001(\0132\035.mavsdk.rpc.telemetry.GpsI" - "nfo\"\030\n\026SubscribeRawGpsRequest\"\?\n\016RawGpsR" - "esponse\022-\n\007raw_gps\030\001 \001(\0132\034.mavsdk.rpc.te" - "lemetry.RawGps\"\031\n\027SubscribeBatteryReques" - "t\"A\n\017BatteryResponse\022.\n\007battery\030\001 \001(\0132\035." - "mavsdk.rpc.telemetry.Battery\"\034\n\032Subscrib" - "eFlightModeRequest\"K\n\022FlightModeResponse" - "\0225\n\013flight_mode\030\001 \001(\0162 .mavsdk.rpc.telem" - "etry.FlightMode\"\030\n\026SubscribeHealthReques" - "t\">\n\016HealthResponse\022,\n\006health\030\001 \001(\0132\034.ma" - "vsdk.rpc.telemetry.Health\"\032\n\030SubscribeRc" - "StatusRequest\"E\n\020RcStatusResponse\0221\n\trc_" - "status\030\001 \001(\0132\036.mavsdk.rpc.telemetry.RcSt" - "atus\"\034\n\032SubscribeStatusTextRequest\"K\n\022St" - "atusTextResponse\0225\n\013status_text\030\001 \001(\0132 ." - "mavsdk.rpc.telemetry.StatusText\"\'\n%Subsc" - "ribeActuatorControlTargetRequest\"m\n\035Actu" - "atorControlTargetResponse\022L\n\027actuator_co" - "ntrol_target\030\001 \001(\0132+.mavsdk.rpc.telemetr" - "y.ActuatorControlTarget\"&\n$SubscribeActu" - "atorOutputStatusRequest\"j\n\034ActuatorOutpu" - "tStatusResponse\022J\n\026actuator_output_statu" - "s\030\001 \001(\0132*.mavsdk.rpc.telemetry.ActuatorO" - "utputStatus\"\032\n\030SubscribeOdometryRequest\"" - "D\n\020OdometryResponse\0220\n\010odometry\030\001 \001(\0132\036." - "mavsdk.rpc.telemetry.Odometry\"%\n#Subscri" - "bePositionVelocityNedRequest\"g\n\033Position" - "VelocityNedResponse\022H\n\025position_velocity" - "_ned\030\001 \001(\0132).mavsdk.rpc.telemetry.Positi" - "onVelocityNed\"\035\n\033SubscribeGroundTruthReq" - "uest\"N\n\023GroundTruthResponse\0227\n\014ground_tr" - "uth\030\001 \001(\0132!.mavsdk.rpc.telemetry.GroundT" - "ruth\"\"\n SubscribeFixedwingMetricsRequest" - "\"]\n\030FixedwingMetricsResponse\022A\n\021fixedwin" - "g_metrics\030\001 \001(\0132&.mavsdk.rpc.telemetry.F" - "ixedwingMetrics\"\025\n\023SubscribeImuRequest\"5" - "\n\013ImuResponse\022&\n\003imu\030\001 \001(\0132\031.mavsdk.rpc." - "telemetry.Imu\"\033\n\031SubscribeScaledImuReque" - "st\";\n\021ScaledImuResponse\022&\n\003imu\030\001 \001(\0132\031.m" - "avsdk.rpc.telemetry.Imu\"\030\n\026SubscribeRawI" - "muRequest\"8\n\016RawImuResponse\022&\n\003imu\030\001 \001(\013" - "2\031.mavsdk.rpc.telemetry.Imu\"\035\n\033Subscribe" - "HealthAllOkRequest\"/\n\023HealthAllOkRespons" - "e\022\030\n\020is_health_all_ok\030\001 \001(\010\"\037\n\035Subscribe" - "UnixEpochTimeRequest\"(\n\025UnixEpochTimeRes" - "ponse\022\017\n\007time_us\030\001 \001(\004\" \n\036SubscribeDista" - "nceSensorRequest\"W\n\026DistanceSensorRespon" - "se\022=\n\017distance_sensor\030\001 \001(\0132$.mavsdk.rpc" - ".telemetry.DistanceSensor\" \n\036SubscribeSc" - "aledPressureRequest\"W\n\026ScaledPressureRes" - "ponse\022=\n\017scaled_pressure\030\001 \001(\0132$.mavsdk." - "rpc.telemetry.ScaledPressure\"\031\n\027Subscrib" - "eHeadingRequest\"E\n\017HeadingResponse\0222\n\013he" - "ading_deg\030\001 \001(\0132\035.mavsdk.rpc.telemetry.H" - "eading\"\032\n\030SubscribeAltitudeRequest\"D\n\020Al" - "titudeResponse\0220\n\010altitude\030\001 \001(\0132\036.mavsd" - "k.rpc.telemetry.Altitude\")\n\026SetRatePosit" - "ionRequest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027SetRatePo" - "sitionResponse\022\?\n\020telemetry_result\030\001 \001(\013" - "2%.mavsdk.rpc.telemetry.TelemetryResult\"" - "%\n\022SetRateHomeRequest\022\017\n\007rate_hz\030\001 \001(\001\"V" - "\n\023SetRateHomeResponse\022\?\n\020telemetry_resul" - "t\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telemetry" - "Result\"&\n\023SetRateInAirRequest\022\017\n\007rate_hz" - "\030\001 \001(\001\"W\n\024SetRateInAirResponse\022\?\n\020teleme" - "try_result\030\001 \001(\0132%.mavsdk.rpc.telemetry." - "TelemetryResult\",\n\031SetRateLandedStateReq" - "uest\022\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRateLandedSt" - "ateResponse\022\?\n\020telemetry_result\030\001 \001(\0132%." - "mavsdk.rpc.telemetry.TelemetryResult\"*\n\027" - "SetRateVtolStateRequest\022\017\n\007rate_hz\030\001 \001(\001" - "\"[\n\030SetRateVtolStateResponse\022\?\n\020telemetr" - "y_result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Te" - "lemetryResult\".\n\033SetRateAttitudeEulerReq" - "uest\022\017\n\007rate_hz\030\001 \001(\001\"_\n\034SetRateAttitude" - "EulerResponse\022\?\n\020telemetry_result\030\001 \001(\0132" - "%.mavsdk.rpc.telemetry.TelemetryResult\"3" - "\n SetRateAttitudeQuaternionRequest\022\017\n\007ra" - "te_hz\030\001 \001(\001\"d\n!SetRateAttitudeQuaternion" - "Response\022\?\n\020telemetry_result\030\001 \001(\0132%.mav" - "sdk.rpc.telemetry.TelemetryResult\"<\n)Set" - "RateAttitudeAngularVelocityBodyRequest\022\017" - "\n\007rate_hz\030\001 \001(\001\"m\n*SetRateAttitudeAngula" - "rVelocityBodyResponse\022\?\n\020telemetry_resul" - "t\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telemetry" - "Result\"9\n&SetRateCameraAttitudeQuaternio" - "nRequest\022\017\n\007rate_hz\030\001 \001(\001\"j\n\'SetRateCame" - "raAttitudeQuaternionResponse\022\?\n\020telemetr" - "y_result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Te" - "lemetryResult\"/\n\034SetRateCameraAttitudeRe" - "quest\022\017\n\007rate_hz\030\001 \001(\001\"`\n\035SetRateCameraA" - "ttitudeResponse\022\?\n\020telemetry_result\030\001 \001(" - "\0132%.mavsdk.rpc.telemetry.TelemetryResult" - "\",\n\031SetRateVelocityNedRequest\022\017\n\007rate_hz" - "\030\001 \001(\001\"]\n\032SetRateVelocityNedResponse\022\?\n\020" - "telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tele" - "metry.TelemetryResult\"(\n\025SetRateGpsInfoR" - "equest\022\017\n\007rate_hz\030\001 \001(\001\"Y\n\026SetRateGpsInf" - "oResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.ma" - "vsdk.rpc.telemetry.TelemetryResult\"\'\n\024Se" - "tRateRawGpsRequest\022\017\n\007rate_hz\030\001 \001(\001\"(\n\025S" - "etRateBatteryRequest\022\017\n\007rate_hz\030\001 \001(\001\"Y\n" - "\026SetRateBatteryResponse\022\?\n\020telemetry_res" + "tyBody\"\035\n\033SubscribeVelocityNedRequest\"N\n" + "\023VelocityNedResponse\0227\n\014velocity_ned\030\001 \001" + "(\0132!.mavsdk.rpc.telemetry.VelocityNed\"\031\n" + "\027SubscribeGpsInfoRequest\"B\n\017GpsInfoRespo" + "nse\022/\n\010gps_info\030\001 \001(\0132\035.mavsdk.rpc.telem" + "etry.GpsInfo\"\030\n\026SubscribeRawGpsRequest\"\?" + "\n\016RawGpsResponse\022-\n\007raw_gps\030\001 \001(\0132\034.mavs" + "dk.rpc.telemetry.RawGps\"\031\n\027SubscribeBatt" + "eryRequest\"A\n\017BatteryResponse\022.\n\007battery" + "\030\001 \001(\0132\035.mavsdk.rpc.telemetry.Battery\"\034\n" + "\032SubscribeFlightModeRequest\"K\n\022FlightMod" + "eResponse\0225\n\013flight_mode\030\001 \001(\0162 .mavsdk." + "rpc.telemetry.FlightMode\"\030\n\026SubscribeHea" + "lthRequest\">\n\016HealthResponse\022,\n\006health\030\001" + " \001(\0132\034.mavsdk.rpc.telemetry.Health\"\032\n\030Su" + "bscribeRcStatusRequest\"E\n\020RcStatusRespon" + "se\0221\n\trc_status\030\001 \001(\0132\036.mavsdk.rpc.telem" + "etry.RcStatus\"\034\n\032SubscribeStatusTextRequ" + "est\"K\n\022StatusTextResponse\0225\n\013status_text" + "\030\001 \001(\0132 .mavsdk.rpc.telemetry.StatusText" + "\"\'\n%SubscribeActuatorControlTargetReques" + "t\"m\n\035ActuatorControlTargetResponse\022L\n\027ac" + "tuator_control_target\030\001 \001(\0132+.mavsdk.rpc" + ".telemetry.ActuatorControlTarget\"&\n$Subs" + "cribeActuatorOutputStatusRequest\"j\n\034Actu" + "atorOutputStatusResponse\022J\n\026actuator_out" + "put_status\030\001 \001(\0132*.mavsdk.rpc.telemetry." + "ActuatorOutputStatus\"\032\n\030SubscribeOdometr" + "yRequest\"D\n\020OdometryResponse\0220\n\010odometry" + "\030\001 \001(\0132\036.mavsdk.rpc.telemetry.Odometry\"%" + "\n#SubscribePositionVelocityNedRequest\"g\n" + "\033PositionVelocityNedResponse\022H\n\025position" + "_velocity_ned\030\001 \001(\0132).mavsdk.rpc.telemet" + "ry.PositionVelocityNed\"\035\n\033SubscribeGroun" + "dTruthRequest\"N\n\023GroundTruthResponse\0227\n\014" + "ground_truth\030\001 \001(\0132!.mavsdk.rpc.telemetr" + "y.GroundTruth\"\"\n SubscribeFixedwingMetri" + "csRequest\"]\n\030FixedwingMetricsResponse\022A\n" + "\021fixedwing_metrics\030\001 \001(\0132&.mavsdk.rpc.te" + "lemetry.FixedwingMetrics\"\025\n\023SubscribeImu" + "Request\"5\n\013ImuResponse\022&\n\003imu\030\001 \001(\0132\031.ma" + "vsdk.rpc.telemetry.Imu\"\033\n\031SubscribeScale" + "dImuRequest\";\n\021ScaledImuResponse\022&\n\003imu\030" + "\001 \001(\0132\031.mavsdk.rpc.telemetry.Imu\"\030\n\026Subs" + "cribeRawImuRequest\"8\n\016RawImuResponse\022&\n\003" + "imu\030\001 \001(\0132\031.mavsdk.rpc.telemetry.Imu\"\035\n\033" + "SubscribeHealthAllOkRequest\"/\n\023HealthAll" + "OkResponse\022\030\n\020is_health_all_ok\030\001 \001(\010\"\037\n\035" + "SubscribeUnixEpochTimeRequest\"(\n\025UnixEpo" + "chTimeResponse\022\017\n\007time_us\030\001 \001(\004\" \n\036Subsc" + "ribeDistanceSensorRequest\"W\n\026DistanceSen" + "sorResponse\022=\n\017distance_sensor\030\001 \001(\0132$.m" + "avsdk.rpc.telemetry.DistanceSensor\" \n\036Su" + "bscribeScaledPressureRequest\"W\n\026ScaledPr" + "essureResponse\022=\n\017scaled_pressure\030\001 \001(\0132" + "$.mavsdk.rpc.telemetry.ScaledPressure\"\031\n" + "\027SubscribeHeadingRequest\"E\n\017HeadingRespo" + "nse\0222\n\013heading_deg\030\001 \001(\0132\035.mavsdk.rpc.te" + "lemetry.Heading\"\032\n\030SubscribeAltitudeRequ" + "est\"D\n\020AltitudeResponse\0220\n\010altitude\030\001 \001(" + "\0132\036.mavsdk.rpc.telemetry.Altitude\")\n\026Set" + "RatePositionRequest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027" + "SetRatePositionResponse\022\?\n\020telemetry_res" "ult\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telemet" - "ryResult\")\n\026SetRateRcStatusRequest\022\017\n\007ra" - "te_hz\030\001 \001(\001\"Z\n\027SetRateRcStatusResponse\022\?" - "\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.te" - "lemetry.TelemetryResult\"6\n#SetRateActuat" - "orControlTargetRequest\022\017\n\007rate_hz\030\001 \001(\001\"" - "g\n$SetRateActuatorControlTargetResponse\022" + "ryResult\"%\n\022SetRateHomeRequest\022\017\n\007rate_h" + "z\030\001 \001(\001\"V\n\023SetRateHomeResponse\022\?\n\020teleme" + "try_result\030\001 \001(\0132%.mavsdk.rpc.telemetry." + "TelemetryResult\"&\n\023SetRateInAirRequest\022\017" + "\n\007rate_hz\030\001 \001(\001\"W\n\024SetRateInAirResponse\022" "\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.t" - "elemetry.TelemetryResult\"5\n\"SetRateActua" - "torOutputStatusRequest\022\017\n\007rate_hz\030\001 \001(\001\"" - "f\n#SetRateActuatorOutputStatusResponse\022\?" - "\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.te" - "lemetry.TelemetryResult\")\n\026SetRateOdomet" - "ryRequest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027SetRateOdo" - "metryResponse\022\?\n\020telemetry_result\030\001 \001(\0132" - "%.mavsdk.rpc.telemetry.TelemetryResult\"4" - "\n!SetRatePositionVelocityNedRequest\022\017\n\007r" - "ate_hz\030\001 \001(\001\"e\n\"SetRatePositionVelocityN" - "edResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.m" - "avsdk.rpc.telemetry.TelemetryResult\",\n\031S" - "etRateGroundTruthRequest\022\017\n\007rate_hz\030\001 \001(" - "\001\"]\n\032SetRateGroundTruthResponse\022\?\n\020telem" - "etry_result\030\001 \001(\0132%.mavsdk.rpc.telemetry" - ".TelemetryResult\"1\n\036SetRateFixedwingMetr" - "icsRequest\022\017\n\007rate_hz\030\001 \001(\001\"b\n\037SetRateFi" - "xedwingMetricsResponse\022\?\n\020telemetry_resu" + "elemetry.TelemetryResult\",\n\031SetRateLande" + "dStateRequest\022\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRat" + "eLandedStateResponse\022\?\n\020telemetry_result" + "\030\001 \001(\0132%.mavsdk.rpc.telemetry.TelemetryR" + "esult\"*\n\027SetRateVtolStateRequest\022\017\n\007rate" + "_hz\030\001 \001(\001\"[\n\030SetRateVtolStateResponse\022\?\n" + "\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tel" + "emetry.TelemetryResult\".\n\033SetRateAttitud" + "eEulerRequest\022\017\n\007rate_hz\030\001 \001(\001\"_\n\034SetRat" + "eAttitudeEulerResponse\022\?\n\020telemetry_resu" "lt\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telemetr" - "yResult\"$\n\021SetRateImuRequest\022\017\n\007rate_hz\030" - "\001 \001(\001\"U\n\022SetRateImuResponse\022\?\n\020telemetry" - "_result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Tel" - "emetryResult\"*\n\027SetRateScaledImuRequest\022" - "\017\n\007rate_hz\030\001 \001(\001\"[\n\030SetRateScaledImuResp" - "onse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk." - "rpc.telemetry.TelemetryResult\"\'\n\024SetRate" - "RawImuRequest\022\017\n\007rate_hz\030\001 \001(\001\"X\n\025SetRat" - "eRawImuResponse\022\?\n\020telemetry_result\030\001 \001(" + "yResult\"3\n SetRateAttitudeQuaternionRequ" + "est\022\017\n\007rate_hz\030\001 \001(\001\"d\n!SetRateAttitudeQ" + "uaternionResponse\022\?\n\020telemetry_result\030\001 " + "\001(\0132%.mavsdk.rpc.telemetry.TelemetryResu" + "lt\"<\n)SetRateAttitudeAngularVelocityBody" + "Request\022\017\n\007rate_hz\030\001 \001(\001\"m\n*SetRateAttit" + "udeAngularVelocityBodyResponse\022\?\n\020teleme" + "try_result\030\001 \001(\0132%.mavsdk.rpc.telemetry." + "TelemetryResult\",\n\031SetRateVelocityNedReq" + "uest\022\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRateVelocity" + "NedResponse\022\?\n\020telemetry_result\030\001 \001(\0132%." + "mavsdk.rpc.telemetry.TelemetryResult\"(\n\025" + "SetRateGpsInfoRequest\022\017\n\007rate_hz\030\001 \001(\001\"Y" + "\n\026SetRateGpsInfoResponse\022\?\n\020telemetry_re" + "sult\030\001 \001(\0132%.mavsdk.rpc.telemetry.Teleme" + "tryResult\"\'\n\024SetRateRawGpsRequest\022\017\n\007rat" + "e_hz\030\001 \001(\001\"(\n\025SetRateBatteryRequest\022\017\n\007r" + "ate_hz\030\001 \001(\001\"Y\n\026SetRateBatteryResponse\022\?" + "\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.te" + "lemetry.TelemetryResult\")\n\026SetRateRcStat" + "usRequest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027SetRateRcS" + "tatusResponse\022\?\n\020telemetry_result\030\001 \001(\0132" + "%.mavsdk.rpc.telemetry.TelemetryResult\"6" + "\n#SetRateActuatorControlTargetRequest\022\017\n" + "\007rate_hz\030\001 \001(\001\"g\n$SetRateActuatorControl" + "TargetResponse\022\?\n\020telemetry_result\030\001 \001(\013" + "2%.mavsdk.rpc.telemetry.TelemetryResult\"" + "5\n\"SetRateActuatorOutputStatusRequest\022\017\n" + "\007rate_hz\030\001 \001(\001\"f\n#SetRateActuatorOutputS" + "tatusResponse\022\?\n\020telemetry_result\030\001 \001(\0132" + "%.mavsdk.rpc.telemetry.TelemetryResult\")" + "\n\026SetRateOdometryRequest\022\017\n\007rate_hz\030\001 \001(" + "\001\"Z\n\027SetRateOdometryResponse\022\?\n\020telemetr" + "y_result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Te" + "lemetryResult\"4\n!SetRatePositionVelocity" + "NedRequest\022\017\n\007rate_hz\030\001 \001(\001\"e\n\"SetRatePo" + "sitionVelocityNedResponse\022\?\n\020telemetry_r" + "esult\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telem" + "etryResult\",\n\031SetRateGroundTruthRequest\022" + "\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRateGroundTruthRe" + "sponse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsd" + "k.rpc.telemetry.TelemetryResult\"1\n\036SetRa" + "teFixedwingMetricsRequest\022\017\n\007rate_hz\030\001 \001" + "(\001\"b\n\037SetRateFixedwingMetricsResponse\022\?\n" + "\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tel" + "emetry.TelemetryResult\"$\n\021SetRateImuRequ" + "est\022\017\n\007rate_hz\030\001 \001(\001\"U\n\022SetRateImuRespon" + "se\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rp" + "c.telemetry.TelemetryResult\"*\n\027SetRateSc" + "aledImuRequest\022\017\n\007rate_hz\030\001 \001(\001\"[\n\030SetRa" + "teScaledImuResponse\022\?\n\020telemetry_result\030" + "\001 \001(\0132%.mavsdk.rpc.telemetry.TelemetryRe" + "sult\"\'\n\024SetRateRawImuRequest\022\017\n\007rate_hz\030" + "\001 \001(\001\"X\n\025SetRateRawImuResponse\022\?\n\020teleme" + "try_result\030\001 \001(\0132%.mavsdk.rpc.telemetry." + "TelemetryResult\".\n\033SetRateUnixEpochTimeR" + "equest\022\017\n\007rate_hz\030\001 \001(\001\"_\n\034SetRateUnixEp" + "ochTimeResponse\022\?\n\020telemetry_result\030\001 \001(" "\0132%.mavsdk.rpc.telemetry.TelemetryResult" - "\".\n\033SetRateUnixEpochTimeRequest\022\017\n\007rate_" - "hz\030\001 \001(\001\"_\n\034SetRateUnixEpochTimeResponse" - "\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc." - "telemetry.TelemetryResult\"/\n\034SetRateDist" - "anceSensorRequest\022\017\n\007rate_hz\030\001 \001(\001\"`\n\035Se" - "tRateDistanceSensorResponse\022\?\n\020telemetry" - "_result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Tel" - "emetryResult\"\033\n\031GetGpsGlobalOriginReques" - "t\"\237\001\n\032GetGpsGlobalOriginResponse\022\?\n\020tele" - "metry_result\030\001 \001(\0132%.mavsdk.rpc.telemetr" - "y.TelemetryResult\022@\n\021gps_global_origin\030\002" - " \001(\0132%.mavsdk.rpc.telemetry.GpsGlobalOri" - "gin\")\n\026SetRateAltitudeRequest\022\017\n\007rate_hz" - "\030\001 \001(\001\"Z\n\027SetRateAltitudeResponse\022\?\n\020tel" - "emetry_result\030\001 \001(\0132%.mavsdk.rpc.telemet" - "ry.TelemetryResult\"\225\001\n\010Position\022\035\n\014latit" - "ude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030" - "\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolute_altitude_m\030\003 " - "\001(\002B\007\202\265\030\003NaN\022$\n\023relative_altitude_m\030\004 \001(" - "\002B\007\202\265\030\003NaN\"\'\n\007Heading\022\034\n\013heading_deg\030\001 \001" - "(\001B\007\202\265\030\003NaN\"r\n\nQuaternion\022\022\n\001w\030\001 \001(\002B\007\202\265" - "\030\003NaN\022\022\n\001x\030\002 \001(\002B\007\202\265\030\003NaN\022\022\n\001y\030\003 \001(\002B\007\202\265" - "\030\003NaN\022\022\n\001z\030\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_u" - "s\030\005 \001(\004\"s\n\nEulerAngle\022\031\n\010roll_deg\030\001 \001(\002B" - "\007\202\265\030\003NaN\022\032\n\tpitch_deg\030\002 \001(\002B\007\202\265\030\003NaN\022\030\n\007" - "yaw_deg\030\003 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_us\030\004" - " \001(\004\"l\n\023AngularVelocityBody\022\033\n\nroll_rad_" - "s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013pitch_rad_s\030\002 \001(\002B\007\202" - "\265\030\003NaN\022\032\n\tyaw_rad_s\030\003 \001(\002B\007\202\265\030\003NaN\"Y\n\007Gp" - "sInfo\022\035\n\016num_satellites\030\001 \001(\005B\005\202\265\030\0010\022/\n\010" - "fix_type\030\002 \001(\0162\035.mavsdk.rpc.telemetry.Fi" - "xType\"\337\002\n\006RawGps\022\024\n\014timestamp_us\030\001 \001(\004\022\024" - "\n\014latitude_deg\030\002 \001(\001\022\025\n\rlongitude_deg\030\003 " - "\001(\001\022\033\n\023absolute_altitude_m\030\004 \001(\002\022\014\n\004hdop" - "\030\005 \001(\002\022\014\n\004vdop\030\006 \001(\002\022\024\n\014velocity_m_s\030\007 \001" - "(\002\022\017\n\007cog_deg\030\010 \001(\002\022\034\n\024altitude_ellipsoi" - "d_m\030\t \001(\002\022 \n\030horizontal_uncertainty_m\030\n " - "\001(\002\022\036\n\026vertical_uncertainty_m\030\013 \001(\002\022 \n\030v" - "elocity_uncertainty_m_s\030\014 \001(\002\022\037\n\027heading" - "_uncertainty_deg\030\r \001(\002\022\017\n\007yaw_deg\030\016 \001(\002\"" - "\312\001\n\007Battery\022\021\n\002id\030\001 \001(\rB\005\202\265\030\0010\022!\n\020temper" - "ature_degc\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tvoltage_v\030\003" - " \001(\002B\007\202\265\030\003NaN\022\"\n\021current_battery_a\030\004 \001(\002" - "B\007\202\265\030\003NaN\022%\n\024capacity_consumed_ah\030\005 \001(\002B" - "\007\202\265\030\003NaN\022\"\n\021remaining_percent\030\006 \001(\002B\007\202\265\030" - "\003NaN\"\271\002\n\006Health\022.\n\033is_gyrometer_calibrat" - "ion_ok\030\001 \001(\010B\t\202\265\030\005false\0222\n\037is_accelerome" - "ter_calibration_ok\030\002 \001(\010B\t\202\265\030\005false\0221\n\036i" - "s_magnetometer_calibration_ok\030\003 \001(\010B\t\202\265\030" - "\005false\022\'\n\024is_local_position_ok\030\005 \001(\010B\t\202\265" - "\030\005false\022(\n\025is_global_position_ok\030\006 \001(\010B\t" - "\202\265\030\005false\022&\n\023is_home_position_ok\030\007 \001(\010B\t" - "\202\265\030\005false\022\035\n\nis_armable\030\010 \001(\010B\t\202\265\030\005false" - "\"|\n\010RcStatus\022%\n\022was_available_once\030\001 \001(\010" - "B\t\202\265\030\005false\022\037\n\014is_available\030\002 \001(\010B\t\202\265\030\005f" - "alse\022(\n\027signal_strength_percent\030\003 \001(\002B\007\202" - "\265\030\003NaN\"N\n\nStatusText\0222\n\004type\030\001 \001(\0162$.mav" - "sdk.rpc.telemetry.StatusTextType\022\014\n\004text" - "\030\002 \001(\t\"\?\n\025ActuatorControlTarget\022\024\n\005group" - "\030\001 \001(\005B\005\202\265\030\0010\022\020\n\010controls\030\002 \003(\002\"\?\n\024Actua" - "torOutputStatus\022\025\n\006active\030\001 \001(\rB\005\202\265\030\0010\022\020" - "\n\010actuator\030\002 \003(\002\"\'\n\nCovariance\022\031\n\021covari" - "ance_matrix\030\001 \003(\002\";\n\014VelocityBody\022\r\n\005x_m" - "_s\030\001 \001(\002\022\r\n\005y_m_s\030\002 \001(\002\022\r\n\005z_m_s\030\003 \001(\002\"5" - "\n\014PositionBody\022\013\n\003x_m\030\001 \001(\002\022\013\n\003y_m\030\002 \001(\002" - "\022\013\n\003z_m\030\003 \001(\002\"\354\004\n\010Odometry\022\021\n\ttime_usec\030" - "\001 \001(\004\0229\n\010frame_id\030\002 \001(\0162\'.mavsdk.rpc.tel" - "emetry.Odometry.MavFrame\022\?\n\016child_frame_" - "id\030\003 \001(\0162\'.mavsdk.rpc.telemetry.Odometry" - ".MavFrame\0229\n\rposition_body\030\004 \001(\0132\".mavsd" - "k.rpc.telemetry.PositionBody\022+\n\001q\030\005 \001(\0132" - " .mavsdk.rpc.telemetry.Quaternion\0229\n\rvel" - "ocity_body\030\006 \001(\0132\".mavsdk.rpc.telemetry." - "VelocityBody\022H\n\025angular_velocity_body\030\007 " - "\001(\0132).mavsdk.rpc.telemetry.AngularVeloci" - "tyBody\0229\n\017pose_covariance\030\010 \001(\0132 .mavsdk" - ".rpc.telemetry.Covariance\022=\n\023velocity_co" - "variance\030\t \001(\0132 .mavsdk.rpc.telemetry.Co" - "variance\"j\n\010MavFrame\022\023\n\017MAV_FRAME_UNDEF\020" - "\000\022\026\n\022MAV_FRAME_BODY_NED\020\010\022\030\n\024MAV_FRAME_V" - "ISION_NED\020\020\022\027\n\023MAV_FRAME_ESTIM_NED\020\022\"\266\001\n" - "\016DistanceSensor\022#\n\022minimum_distance_m\030\001 " - "\001(\002B\007\202\265\030\003NaN\022#\n\022maximum_distance_m\030\002 \001(\002" - "B\007\202\265\030\003NaN\022#\n\022current_distance_m\030\003 \001(\002B\007\202" - "\265\030\003NaN\0225\n\013orientation\030\004 \001(\0132 .mavsdk.rpc" - ".telemetry.EulerAngle\"\260\001\n\016ScaledPressure" - "\022\024\n\014timestamp_us\030\001 \001(\004\022\035\n\025absolute_press" - "ure_hpa\030\002 \001(\002\022!\n\031differential_pressure_h" - "pa\030\003 \001(\002\022\027\n\017temperature_deg\030\004 \001(\002\022-\n%dif" - "ferential_pressure_temperature_deg\030\005 \001(\002" - "\"Y\n\013PositionNed\022\030\n\007north_m\030\001 \001(\002B\007\202\265\030\003Na" - "N\022\027\n\006east_m\030\002 \001(\002B\007\202\265\030\003NaN\022\027\n\006down_m\030\003 \001" - "(\002B\007\202\265\030\003NaN\"D\n\013VelocityNed\022\021\n\tnorth_m_s\030" - "\001 \001(\002\022\020\n\010east_m_s\030\002 \001(\002\022\020\n\010down_m_s\030\003 \001(" - "\002\"\177\n\023PositionVelocityNed\0223\n\010position\030\001 \001" - "(\0132!.mavsdk.rpc.telemetry.PositionNed\0223\n" - "\010velocity\030\002 \001(\0132!.mavsdk.rpc.telemetry.V" - "elocityNed\"r\n\013GroundTruth\022\035\n\014latitude_de" - "g\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001(\001B" - "\007\202\265\030\003NaN\022$\n\023absolute_altitude_m\030\003 \001(\002B\007\202" - "\265\030\003NaN\"x\n\020FixedwingMetrics\022\035\n\014airspeed_m" - "_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023throttle_percentage" - "\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb_rate_m_s\030\003 \001(\002B" - "\007\202\265\030\003NaN\"i\n\017AccelerationFrd\022\035\n\014forward_m" - "_s2\030\001 \001(\002B\007\202\265\030\003NaN\022\033\n\nright_m_s2\030\002 \001(\002B\007" - "\202\265\030\003NaN\022\032\n\tdown_m_s2\030\003 \001(\002B\007\202\265\030\003NaN\"o\n\022A" - "ngularVelocityFrd\022\036\n\rforward_rad_s\030\001 \001(\002" - "B\007\202\265\030\003NaN\022\034\n\013right_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022" - "\033\n\ndown_rad_s\030\003 \001(\002B\007\202\265\030\003NaN\"m\n\020Magnetic" - "FieldFrd\022\036\n\rforward_gauss\030\001 \001(\002B\007\202\265\030\003NaN" - "\022\034\n\013right_gauss\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_g" - "auss\030\003 \001(\002B\007\202\265\030\003NaN\"\213\002\n\003Imu\022\?\n\020accelerat" - "ion_frd\030\001 \001(\0132%.mavsdk.rpc.telemetry.Acc" - "elerationFrd\022F\n\024angular_velocity_frd\030\002 \001" - "(\0132(.mavsdk.rpc.telemetry.AngularVelocit" - "yFrd\022B\n\022magnetic_field_frd\030\003 \001(\0132&.mavsd" - "k.rpc.telemetry.MagneticFieldFrd\022!\n\020temp" - "erature_degc\030\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp" - "_us\030\005 \001(\004\"m\n\017GpsGlobalOrigin\022\035\n\014latitude" - "_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001" - "(\001B\007\202\265\030\003NaN\022\033\n\naltitude_m\030\003 \001(\002B\007\202\265\030\003NaN" - "\"\346\001\n\010Altitude\022%\n\024altitude_monotonic_m\030\001 " - "\001(\002B\007\202\265\030\003NaN\022 \n\017altitude_amsl_m\030\002 \001(\002B\007\202" - "\265\030\003NaN\022!\n\020altitude_local_m\030\003 \001(\002B\007\202\265\030\003Na" - "N\022$\n\023altitude_relative_m\030\004 \001(\002B\007\202\265\030\003NaN\022" - "#\n\022altitude_terrain_m\030\005 \001(\002B\007\202\265\030\003NaN\022#\n\022" - "bottom_clearance_m\030\006 \001(\002B\007\202\265\030\003NaN\"\241\002\n\017Te" - "lemetryResult\022<\n\006result\030\001 \001(\0162,.mavsdk.r" - "pc.telemetry.TelemetryResult.Result\022\022\n\nr" - "esult_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RESULT_UNK" - "NOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NO_" - "SYSTEM\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022\017\n" - "\013RESULT_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIED\020" - "\005\022\022\n\016RESULT_TIMEOUT\020\006\022\026\n\022RESULT_UNSUPPOR" - "TED\020\007*\244\001\n\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023" - "\n\017FIX_TYPE_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002" - "\022\023\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DG" - "PS\020\004\022\026\n\022FIX_TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE" - "_RTK_FIXED\020\006*\206\003\n\nFlightMode\022\027\n\023FLIGHT_MO" - "DE_UNKNOWN\020\000\022\025\n\021FLIGHT_MODE_READY\020\001\022\027\n\023F" - "LIGHT_MODE_TAKEOFF\020\002\022\024\n\020FLIGHT_MODE_HOLD" - "\020\003\022\027\n\023FLIGHT_MODE_MISSION\020\004\022 \n\034FLIGHT_MO" - "DE_RETURN_TO_LAUNCH\020\005\022\024\n\020FLIGHT_MODE_LAN" - "D\020\006\022\030\n\024FLIGHT_MODE_OFFBOARD\020\007\022\031\n\025FLIGHT_" - "MODE_FOLLOW_ME\020\010\022\026\n\022FLIGHT_MODE_MANUAL\020\t" - "\022\026\n\022FLIGHT_MODE_ALTCTL\020\n\022\026\n\022FLIGHT_MODE_" - "POSCTL\020\013\022\024\n\020FLIGHT_MODE_ACRO\020\014\022\032\n\026FLIGHT" - "_MODE_STABILIZED\020\r\022\031\n\025FLIGHT_MODE_RATTIT" - "UDE\020\016*\371\001\n\016StatusTextType\022\032\n\026STATUS_TEXT_" - "TYPE_DEBUG\020\000\022\031\n\025STATUS_TEXT_TYPE_INFO\020\001\022" - "\033\n\027STATUS_TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_T" - "EXT_TYPE_WARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_E" - "RROR\020\004\022\035\n\031STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n" - "\026STATUS_TEXT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT" - "_TYPE_EMERGENCY\020\007*\223\001\n\013LandedState\022\030\n\024LAN" - "DED_STATE_UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_G" - "ROUND\020\001\022\027\n\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LAND" - "ED_STATE_TAKING_OFF\020\003\022\030\n\024LANDED_STATE_LA" - "NDING\020\004*\215\001\n\tVtolState\022\030\n\024VTOL_STATE_UNDE" - "FINED\020\000\022\037\n\033VTOL_STATE_TRANSITION_TO_FW\020\001" - "\022\037\n\033VTOL_STATE_TRANSITION_TO_MC\020\002\022\021\n\rVTO" - "L_STATE_MC\020\003\022\021\n\rVTOL_STATE_FW\020\0042\2019\n\020Tele" - "metryService\022o\n\021SubscribePosition\022..mavs" - "dk.rpc.telemetry.SubscribePositionReques" - "t\032&.mavsdk.rpc.telemetry.PositionRespons" - "e\"\0000\001\022c\n\rSubscribeHome\022*.mavsdk.rpc.tele" - "metry.SubscribeHomeRequest\032\".mavsdk.rpc." - "telemetry.HomeResponse\"\0000\001\022f\n\016SubscribeI" - "nAir\022+.mavsdk.rpc.telemetry.SubscribeInA" - "irRequest\032#.mavsdk.rpc.telemetry.InAirRe" - "sponse\"\0000\001\022x\n\024SubscribeLandedState\0221.mav" - "sdk.rpc.telemetry.SubscribeLandedStateRe" - "quest\032).mavsdk.rpc.telemetry.LandedState" - "Response\"\0000\001\022f\n\016SubscribeArmed\022+.mavsdk." - "rpc.telemetry.SubscribeArmedRequest\032#.ma" - "vsdk.rpc.telemetry.ArmedResponse\"\0000\001\022r\n\022" - "SubscribeVtolState\022/.mavsdk.rpc.telemetr" - "y.SubscribeVtolStateRequest\032\'.mavsdk.rpc" - ".telemetry.VtolStateResponse\"\0000\001\022\215\001\n\033Sub" - "scribeAttitudeQuaternion\0228.mavsdk.rpc.te" - "lemetry.SubscribeAttitudeQuaternionReque" - "st\0320.mavsdk.rpc.telemetry.AttitudeQuater" - "nionResponse\"\0000\001\022~\n\026SubscribeAttitudeEul" - "er\0223.mavsdk.rpc.telemetry.SubscribeAttit" - "udeEulerRequest\032+.mavsdk.rpc.telemetry.A" - "ttitudeEulerResponse\"\0000\001\022\250\001\n$SubscribeAt" - "titudeAngularVelocityBody\022A.mavsdk.rpc.t" - "elemetry.SubscribeAttitudeAngularVelocit" - "yBodyRequest\0329.mavsdk.rpc.telemetry.Atti" - "tudeAngularVelocityBodyResponse\"\0000\001\022\237\001\n!" - "SubscribeCameraAttitudeQuaternion\022>.mavs" - "dk.rpc.telemetry.SubscribeCameraAttitude" - "QuaternionRequest\0326.mavsdk.rpc.telemetry" - ".CameraAttitudeQuaternionResponse\"\0000\001\022\220\001" - "\n\034SubscribeCameraAttitudeEuler\0229.mavsdk." - "rpc.telemetry.SubscribeCameraAttitudeEul" - "erRequest\0321.mavsdk.rpc.telemetry.CameraA" - "ttitudeEulerResponse\"\0000\001\022x\n\024SubscribeVel" - "ocityNed\0221.mavsdk.rpc.telemetry.Subscrib" - "eVelocityNedRequest\032).mavsdk.rpc.telemet" - "ry.VelocityNedResponse\"\0000\001\022l\n\020SubscribeG" - "psInfo\022-.mavsdk.rpc.telemetry.SubscribeG" - "psInfoRequest\032%.mavsdk.rpc.telemetry.Gps" - "InfoResponse\"\0000\001\022i\n\017SubscribeRawGps\022,.ma" - "vsdk.rpc.telemetry.SubscribeRawGpsReques" - "t\032$.mavsdk.rpc.telemetry.RawGpsResponse\"" - "\0000\001\022l\n\020SubscribeBattery\022-.mavsdk.rpc.tel" - "emetry.SubscribeBatteryRequest\032%.mavsdk." - "rpc.telemetry.BatteryResponse\"\0000\001\022u\n\023Sub" - "scribeFlightMode\0220.mavsdk.rpc.telemetry." - "SubscribeFlightModeRequest\032(.mavsdk.rpc." - "telemetry.FlightModeResponse\"\0000\001\022i\n\017Subs" - "cribeHealth\022,.mavsdk.rpc.telemetry.Subsc" - "ribeHealthRequest\032$.mavsdk.rpc.telemetry" - ".HealthResponse\"\0000\001\022o\n\021SubscribeRcStatus" - "\022..mavsdk.rpc.telemetry.SubscribeRcStatu" - "sRequest\032&.mavsdk.rpc.telemetry.RcStatus" - "Response\"\0000\001\022u\n\023SubscribeStatusText\0220.ma" - "vsdk.rpc.telemetry.SubscribeStatusTextRe" - "quest\032(.mavsdk.rpc.telemetry.StatusTextR" - "esponse\"\0000\001\022\226\001\n\036SubscribeActuatorControl" - "Target\022;.mavsdk.rpc.telemetry.SubscribeA" - "ctuatorControlTargetRequest\0323.mavsdk.rpc" - ".telemetry.ActuatorControlTargetResponse" - "\"\0000\001\022\223\001\n\035SubscribeActuatorOutputStatus\022:" - ".mavsdk.rpc.telemetry.SubscribeActuatorO" - "utputStatusRequest\0322.mavsdk.rpc.telemetr" - "y.ActuatorOutputStatusResponse\"\0000\001\022o\n\021Su" - "bscribeOdometry\022..mavsdk.rpc.telemetry.S" - "ubscribeOdometryRequest\032&.mavsdk.rpc.tel" - "emetry.OdometryResponse\"\0000\001\022\220\001\n\034Subscrib" - "ePositionVelocityNed\0229.mavsdk.rpc.teleme" - "try.SubscribePositionVelocityNedRequest\032" - "1.mavsdk.rpc.telemetry.PositionVelocityN" - "edResponse\"\0000\001\022x\n\024SubscribeGroundTruth\0221" - ".mavsdk.rpc.telemetry.SubscribeGroundTru" - "thRequest\032).mavsdk.rpc.telemetry.GroundT" - "ruthResponse\"\0000\001\022\207\001\n\031SubscribeFixedwingM" - "etrics\0226.mavsdk.rpc.telemetry.SubscribeF" - "ixedwingMetricsRequest\032..mavsdk.rpc.tele" - "metry.FixedwingMetricsResponse\"\0000\001\022`\n\014Su" - "bscribeImu\022).mavsdk.rpc.telemetry.Subscr" - "ibeImuRequest\032!.mavsdk.rpc.telemetry.Imu" - "Response\"\0000\001\022r\n\022SubscribeScaledImu\022/.mav" - "sdk.rpc.telemetry.SubscribeScaledImuRequ" - "est\032\'.mavsdk.rpc.telemetry.ScaledImuResp" - "onse\"\0000\001\022i\n\017SubscribeRawImu\022,.mavsdk.rpc" - ".telemetry.SubscribeRawImuRequest\032$.mavs" - "dk.rpc.telemetry.RawImuResponse\"\0000\001\022x\n\024S" - "ubscribeHealthAllOk\0221.mavsdk.rpc.telemet" - "ry.SubscribeHealthAllOkRequest\032).mavsdk." - "rpc.telemetry.HealthAllOkResponse\"\0000\001\022~\n" - "\026SubscribeUnixEpochTime\0223.mavsdk.rpc.tel" - "emetry.SubscribeUnixEpochTimeRequest\032+.m" - "avsdk.rpc.telemetry.UnixEpochTimeRespons" - "e\"\0000\001\022\201\001\n\027SubscribeDistanceSensor\0224.mavs" - "dk.rpc.telemetry.SubscribeDistanceSensor" - "Request\032,.mavsdk.rpc.telemetry.DistanceS" - "ensorResponse\"\0000\001\022\201\001\n\027SubscribeScaledPre" - "ssure\0224.mavsdk.rpc.telemetry.SubscribeSc" - "aledPressureRequest\032,.mavsdk.rpc.telemet" - "ry.ScaledPressureResponse\"\0000\001\022l\n\020Subscri" - "beHeading\022-.mavsdk.rpc.telemetry.Subscri" - "beHeadingRequest\032%.mavsdk.rpc.telemetry." - "HeadingResponse\"\0000\001\022o\n\021SubscribeAltitude" - "\022..mavsdk.rpc.telemetry.SubscribeAltitud" - "eRequest\032&.mavsdk.rpc.telemetry.Altitude" - "Response\"\0000\001\022p\n\017SetRatePosition\022,.mavsdk" - ".rpc.telemetry.SetRatePositionRequest\032-." - "mavsdk.rpc.telemetry.SetRatePositionResp" - "onse\"\000\022d\n\013SetRateHome\022(.mavsdk.rpc.telem" - "etry.SetRateHomeRequest\032).mavsdk.rpc.tel" - "emetry.SetRateHomeResponse\"\000\022g\n\014SetRateI" - "nAir\022).mavsdk.rpc.telemetry.SetRateInAir" - "Request\032*.mavsdk.rpc.telemetry.SetRateIn" - "AirResponse\"\000\022y\n\022SetRateLandedState\022/.ma" - "vsdk.rpc.telemetry.SetRateLandedStateReq" - "uest\0320.mavsdk.rpc.telemetry.SetRateLande" - "dStateResponse\"\000\022s\n\020SetRateVtolState\022-.m" - "avsdk.rpc.telemetry.SetRateVtolStateRequ" - "est\032..mavsdk.rpc.telemetry.SetRateVtolSt" - "ateResponse\"\000\022\216\001\n\031SetRateAttitudeQuatern" - "ion\0226.mavsdk.rpc.telemetry.SetRateAttitu" - "deQuaternionRequest\0327.mavsdk.rpc.telemet" - "ry.SetRateAttitudeQuaternionResponse\"\000\022\177" - "\n\024SetRateAttitudeEuler\0221.mavsdk.rpc.tele" - "metry.SetRateAttitudeEulerRequest\0322.mavs" - "dk.rpc.telemetry.SetRateAttitudeEulerRes" - "ponse\"\000\022\202\001\n\025SetRateCameraAttitude\0222.mavs" - "dk.rpc.telemetry.SetRateCameraAttitudeRe" - "quest\0323.mavsdk.rpc.telemetry.SetRateCame" - "raAttitudeResponse\"\000\022y\n\022SetRateVelocityN" - "ed\022/.mavsdk.rpc.telemetry.SetRateVelocit" - "yNedRequest\0320.mavsdk.rpc.telemetry.SetRa" - "teVelocityNedResponse\"\000\022m\n\016SetRateGpsInf" - "o\022+.mavsdk.rpc.telemetry.SetRateGpsInfoR" - "equest\032,.mavsdk.rpc.telemetry.SetRateGps" - "InfoResponse\"\000\022m\n\016SetRateBattery\022+.mavsd" - "k.rpc.telemetry.SetRateBatteryRequest\032,." - "mavsdk.rpc.telemetry.SetRateBatteryRespo" - "nse\"\000\022p\n\017SetRateRcStatus\022,.mavsdk.rpc.te" - "lemetry.SetRateRcStatusRequest\032-.mavsdk." - "rpc.telemetry.SetRateRcStatusResponse\"\000\022" - "\227\001\n\034SetRateActuatorControlTarget\0229.mavsd" - "k.rpc.telemetry.SetRateActuatorControlTa" - "rgetRequest\032:.mavsdk.rpc.telemetry.SetRa" - "teActuatorControlTargetResponse\"\000\022\224\001\n\033Se" - "tRateActuatorOutputStatus\0228.mavsdk.rpc.t" - "elemetry.SetRateActuatorOutputStatusRequ" - "est\0329.mavsdk.rpc.telemetry.SetRateActuat" - "orOutputStatusResponse\"\000\022p\n\017SetRateOdome" - "try\022,.mavsdk.rpc.telemetry.SetRateOdomet" - "ryRequest\032-.mavsdk.rpc.telemetry.SetRate" - "OdometryResponse\"\000\022\221\001\n\032SetRatePositionVe" - "locityNed\0227.mavsdk.rpc.telemetry.SetRate" - "PositionVelocityNedRequest\0328.mavsdk.rpc." - "telemetry.SetRatePositionVelocityNedResp" - "onse\"\000\022y\n\022SetRateGroundTruth\022/.mavsdk.rp" - "c.telemetry.SetRateGroundTruthRequest\0320." - "mavsdk.rpc.telemetry.SetRateGroundTruthR" - "esponse\"\000\022\210\001\n\027SetRateFixedwingMetrics\0224." - "mavsdk.rpc.telemetry.SetRateFixedwingMet" - "ricsRequest\0325.mavsdk.rpc.telemetry.SetRa" - "teFixedwingMetricsResponse\"\000\022a\n\nSetRateI" - "mu\022\'.mavsdk.rpc.telemetry.SetRateImuRequ" - "est\032(.mavsdk.rpc.telemetry.SetRateImuRes" - "ponse\"\000\022s\n\020SetRateScaledImu\022-.mavsdk.rpc" - ".telemetry.SetRateScaledImuRequest\032..mav" - "sdk.rpc.telemetry.SetRateScaledImuRespon" - "se\"\000\022j\n\rSetRateRawImu\022*.mavsdk.rpc.telem" - "etry.SetRateRawImuRequest\032+.mavsdk.rpc.t" - "elemetry.SetRateRawImuResponse\"\000\022\177\n\024SetR" - "ateUnixEpochTime\0221.mavsdk.rpc.telemetry." - "SetRateUnixEpochTimeRequest\0322.mavsdk.rpc" - ".telemetry.SetRateUnixEpochTimeResponse\"" - "\000\022\202\001\n\025SetRateDistanceSensor\0222.mavsdk.rpc" - ".telemetry.SetRateDistanceSensorRequest\032" - "3.mavsdk.rpc.telemetry.SetRateDistanceSe" - "nsorResponse\"\000\022p\n\017SetRateAltitude\022,.mavs" - "dk.rpc.telemetry.SetRateAltitudeRequest\032" - "-.mavsdk.rpc.telemetry.SetRateAltitudeRe" - "sponse\"\000\022y\n\022GetGpsGlobalOrigin\022/.mavsdk." - "rpc.telemetry.GetGpsGlobalOriginRequest\032" - "0.mavsdk.rpc.telemetry.GetGpsGlobalOrigi" - "nResponse\"\000B%\n\023io.mavsdk.telemetryB\016Tele" - "metryProtob\006proto3" + "\"/\n\034SetRateDistanceSensorRequest\022\017\n\007rate" + "_hz\030\001 \001(\001\"`\n\035SetRateDistanceSensorRespon" + "se\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.rp" + "c.telemetry.TelemetryResult\"\033\n\031GetGpsGlo" + "balOriginRequest\"\237\001\n\032GetGpsGlobalOriginR" + "esponse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavs" + "dk.rpc.telemetry.TelemetryResult\022@\n\021gps_" + "global_origin\030\002 \001(\0132%.mavsdk.rpc.telemet" + "ry.GpsGlobalOrigin\")\n\026SetRateAltitudeReq" + "uest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027SetRateAltitude" + "Response\022\?\n\020telemetry_result\030\001 \001(\0132%.mav" + "sdk.rpc.telemetry.TelemetryResult\"\225\001\n\010Po" + "sition\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n" + "\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolut" + "e_altitude_m\030\003 \001(\002B\007\202\265\030\003NaN\022$\n\023relative_" + "altitude_m\030\004 \001(\002B\007\202\265\030\003NaN\"\'\n\007Heading\022\034\n\013" + "heading_deg\030\001 \001(\001B\007\202\265\030\003NaN\"r\n\nQuaternion" + "\022\022\n\001w\030\001 \001(\002B\007\202\265\030\003NaN\022\022\n\001x\030\002 \001(\002B\007\202\265\030\003NaN" + "\022\022\n\001y\030\003 \001(\002B\007\202\265\030\003NaN\022\022\n\001z\030\004 \001(\002B\007\202\265\030\003NaN" + "\022\024\n\014timestamp_us\030\005 \001(\004\"s\n\nEulerAngle\022\031\n\010" + "roll_deg\030\001 \001(\002B\007\202\265\030\003NaN\022\032\n\tpitch_deg\030\002 \001" + "(\002B\007\202\265\030\003NaN\022\030\n\007yaw_deg\030\003 \001(\002B\007\202\265\030\003NaN\022\024\n" + "\014timestamp_us\030\004 \001(\004\"l\n\023AngularVelocityBo" + "dy\022\033\n\nroll_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013pitch" + "_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tyaw_rad_s\030\003 \001(\002" + "B\007\202\265\030\003NaN\"Y\n\007GpsInfo\022\035\n\016num_satellites\030\001" + " \001(\005B\005\202\265\030\0010\022/\n\010fix_type\030\002 \001(\0162\035.mavsdk.r" + "pc.telemetry.FixType\"\337\002\n\006RawGps\022\024\n\014times" + "tamp_us\030\001 \001(\004\022\024\n\014latitude_deg\030\002 \001(\001\022\025\n\rl" + "ongitude_deg\030\003 \001(\001\022\033\n\023absolute_altitude_" + "m\030\004 \001(\002\022\014\n\004hdop\030\005 \001(\002\022\014\n\004vdop\030\006 \001(\002\022\024\n\014v" + "elocity_m_s\030\007 \001(\002\022\017\n\007cog_deg\030\010 \001(\002\022\034\n\024al" + "titude_ellipsoid_m\030\t \001(\002\022 \n\030horizontal_u" + "ncertainty_m\030\n \001(\002\022\036\n\026vertical_uncertain" + "ty_m\030\013 \001(\002\022 \n\030velocity_uncertainty_m_s\030\014" + " \001(\002\022\037\n\027heading_uncertainty_deg\030\r \001(\002\022\017\n" + "\007yaw_deg\030\016 \001(\002\"\312\001\n\007Battery\022\021\n\002id\030\001 \001(\rB\005" + "\202\265\030\0010\022!\n\020temperature_degc\030\002 \001(\002B\007\202\265\030\003NaN" + "\022\032\n\tvoltage_v\030\003 \001(\002B\007\202\265\030\003NaN\022\"\n\021current_" + "battery_a\030\004 \001(\002B\007\202\265\030\003NaN\022%\n\024capacity_con" + "sumed_ah\030\005 \001(\002B\007\202\265\030\003NaN\022\"\n\021remaining_per" + "cent\030\006 \001(\002B\007\202\265\030\003NaN\"\271\002\n\006Health\022.\n\033is_gyr" + "ometer_calibration_ok\030\001 \001(\010B\t\202\265\030\005false\0222" + "\n\037is_accelerometer_calibration_ok\030\002 \001(\010B" + "\t\202\265\030\005false\0221\n\036is_magnetometer_calibratio" + "n_ok\030\003 \001(\010B\t\202\265\030\005false\022\'\n\024is_local_positi" + "on_ok\030\005 \001(\010B\t\202\265\030\005false\022(\n\025is_global_posi" + "tion_ok\030\006 \001(\010B\t\202\265\030\005false\022&\n\023is_home_posi" + "tion_ok\030\007 \001(\010B\t\202\265\030\005false\022\035\n\nis_armable\030\010" + " \001(\010B\t\202\265\030\005false\"|\n\010RcStatus\022%\n\022was_avail" + "able_once\030\001 \001(\010B\t\202\265\030\005false\022\037\n\014is_availab" + "le\030\002 \001(\010B\t\202\265\030\005false\022(\n\027signal_strength_p" + "ercent\030\003 \001(\002B\007\202\265\030\003NaN\"N\n\nStatusText\0222\n\004t" + "ype\030\001 \001(\0162$.mavsdk.rpc.telemetry.StatusT" + "extType\022\014\n\004text\030\002 \001(\t\"\?\n\025ActuatorControl" + "Target\022\024\n\005group\030\001 \001(\005B\005\202\265\030\0010\022\020\n\010controls" + "\030\002 \003(\002\"\?\n\024ActuatorOutputStatus\022\025\n\006active" + "\030\001 \001(\rB\005\202\265\030\0010\022\020\n\010actuator\030\002 \003(\002\"\'\n\nCovar" + "iance\022\031\n\021covariance_matrix\030\001 \003(\002\";\n\014Velo" + "cityBody\022\r\n\005x_m_s\030\001 \001(\002\022\r\n\005y_m_s\030\002 \001(\002\022\r" + "\n\005z_m_s\030\003 \001(\002\"5\n\014PositionBody\022\013\n\003x_m\030\001 \001" + "(\002\022\013\n\003y_m\030\002 \001(\002\022\013\n\003z_m\030\003 \001(\002\"\354\004\n\010Odometr" + "y\022\021\n\ttime_usec\030\001 \001(\004\0229\n\010frame_id\030\002 \001(\0162\'" + ".mavsdk.rpc.telemetry.Odometry.MavFrame\022" + "\?\n\016child_frame_id\030\003 \001(\0162\'.mavsdk.rpc.tel" + "emetry.Odometry.MavFrame\0229\n\rposition_bod" + "y\030\004 \001(\0132\".mavsdk.rpc.telemetry.PositionB" + "ody\022+\n\001q\030\005 \001(\0132 .mavsdk.rpc.telemetry.Qu" + "aternion\0229\n\rvelocity_body\030\006 \001(\0132\".mavsdk" + ".rpc.telemetry.VelocityBody\022H\n\025angular_v" + "elocity_body\030\007 \001(\0132).mavsdk.rpc.telemetr" + "y.AngularVelocityBody\0229\n\017pose_covariance" + "\030\010 \001(\0132 .mavsdk.rpc.telemetry.Covariance" + "\022=\n\023velocity_covariance\030\t \001(\0132 .mavsdk.r" + "pc.telemetry.Covariance\"j\n\010MavFrame\022\023\n\017M" + "AV_FRAME_UNDEF\020\000\022\026\n\022MAV_FRAME_BODY_NED\020\010" + "\022\030\n\024MAV_FRAME_VISION_NED\020\020\022\027\n\023MAV_FRAME_" + "ESTIM_NED\020\022\"\266\001\n\016DistanceSensor\022#\n\022minimu" + "m_distance_m\030\001 \001(\002B\007\202\265\030\003NaN\022#\n\022maximum_d" + "istance_m\030\002 \001(\002B\007\202\265\030\003NaN\022#\n\022current_dist" + "ance_m\030\003 \001(\002B\007\202\265\030\003NaN\0225\n\013orientation\030\004 \001" + "(\0132 .mavsdk.rpc.telemetry.EulerAngle\"\260\001\n" + "\016ScaledPressure\022\024\n\014timestamp_us\030\001 \001(\004\022\035\n" + "\025absolute_pressure_hpa\030\002 \001(\002\022!\n\031differen" + "tial_pressure_hpa\030\003 \001(\002\022\027\n\017temperature_d" + "eg\030\004 \001(\002\022-\n%differential_pressure_temper" + "ature_deg\030\005 \001(\002\"Y\n\013PositionNed\022\030\n\007north_" + "m\030\001 \001(\002B\007\202\265\030\003NaN\022\027\n\006east_m\030\002 \001(\002B\007\202\265\030\003Na" + "N\022\027\n\006down_m\030\003 \001(\002B\007\202\265\030\003NaN\"D\n\013VelocityNe" + "d\022\021\n\tnorth_m_s\030\001 \001(\002\022\020\n\010east_m_s\030\002 \001(\002\022\020" + "\n\010down_m_s\030\003 \001(\002\"\177\n\023PositionVelocityNed\022" + "3\n\010position\030\001 \001(\0132!.mavsdk.rpc.telemetry" + ".PositionNed\0223\n\010velocity\030\002 \001(\0132!.mavsdk." + "rpc.telemetry.VelocityNed\"r\n\013GroundTruth" + "\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongi" + "tude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolute_alti" + "tude_m\030\003 \001(\002B\007\202\265\030\003NaN\"x\n\020FixedwingMetric" + "s\022\035\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023thro" + "ttle_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb_" + "rate_m_s\030\003 \001(\002B\007\202\265\030\003NaN\"i\n\017AccelerationF" + "rd\022\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003NaN\022\033\n\nrig" + "ht_m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m_s2\030\003 \001(" + "\002B\007\202\265\030\003NaN\"o\n\022AngularVelocityFrd\022\036\n\rforw" + "ard_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_rad_s\030" + "\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001(\002B\007\202\265\030\003" + "NaN\"m\n\020MagneticFieldFrd\022\036\n\rforward_gauss" + "\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002 \001(\002B\007\202\265" + "\030\003NaN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003NaN\"\213\002\n\003I" + "mu\022\?\n\020acceleration_frd\030\001 \001(\0132%.mavsdk.rp" + "c.telemetry.AccelerationFrd\022F\n\024angular_v" + "elocity_frd\030\002 \001(\0132(.mavsdk.rpc.telemetry" + ".AngularVelocityFrd\022B\n\022magnetic_field_fr" + "d\030\003 \001(\0132&.mavsdk.rpc.telemetry.MagneticF" + "ieldFrd\022!\n\020temperature_degc\030\004 \001(\002B\007\202\265\030\003N" + "aN\022\024\n\014timestamp_us\030\005 \001(\004\"m\n\017GpsGlobalOri" + "gin\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlo" + "ngitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022\033\n\naltitude_m" + "\030\003 \001(\002B\007\202\265\030\003NaN\"\346\001\n\010Altitude\022%\n\024altitude" + "_monotonic_m\030\001 \001(\002B\007\202\265\030\003NaN\022 \n\017altitude_" + "amsl_m\030\002 \001(\002B\007\202\265\030\003NaN\022!\n\020altitude_local_" + "m\030\003 \001(\002B\007\202\265\030\003NaN\022$\n\023altitude_relative_m\030" + "\004 \001(\002B\007\202\265\030\003NaN\022#\n\022altitude_terrain_m\030\005 \001" + "(\002B\007\202\265\030\003NaN\022#\n\022bottom_clearance_m\030\006 \001(\002B" + "\007\202\265\030\003NaN\"\241\002\n\017TelemetryResult\022<\n\006result\030\001" + " \001(\0162,.mavsdk.rpc.telemetry.TelemetryRes" + "ult.Result\022\022\n\nresult_str\030\002 \001(\t\"\273\001\n\006Resul" + "t\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020" + "\001\022\024\n\020RESULT_NO_SYSTEM\020\002\022\033\n\027RESULT_CONNEC" + "TION_ERROR\020\003\022\017\n\013RESULT_BUSY\020\004\022\031\n\025RESULT_" + "COMMAND_DENIED\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\026\n\022" + "RESULT_UNSUPPORTED\020\007*\244\001\n\007FixType\022\023\n\017FIX_" + "TYPE_NO_GPS\020\000\022\023\n\017FIX_TYPE_NO_FIX\020\001\022\023\n\017FI" + "X_TYPE_FIX_2D\020\002\022\023\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021" + "FIX_TYPE_FIX_DGPS\020\004\022\026\n\022FIX_TYPE_RTK_FLOA" + "T\020\005\022\026\n\022FIX_TYPE_RTK_FIXED\020\006*\206\003\n\nFlightMo" + "de\022\027\n\023FLIGHT_MODE_UNKNOWN\020\000\022\025\n\021FLIGHT_MO" + "DE_READY\020\001\022\027\n\023FLIGHT_MODE_TAKEOFF\020\002\022\024\n\020F" + "LIGHT_MODE_HOLD\020\003\022\027\n\023FLIGHT_MODE_MISSION" + "\020\004\022 \n\034FLIGHT_MODE_RETURN_TO_LAUNCH\020\005\022\024\n\020" + "FLIGHT_MODE_LAND\020\006\022\030\n\024FLIGHT_MODE_OFFBOA" + "RD\020\007\022\031\n\025FLIGHT_MODE_FOLLOW_ME\020\010\022\026\n\022FLIGH" + "T_MODE_MANUAL\020\t\022\026\n\022FLIGHT_MODE_ALTCTL\020\n\022" + "\026\n\022FLIGHT_MODE_POSCTL\020\013\022\024\n\020FLIGHT_MODE_A" + "CRO\020\014\022\032\n\026FLIGHT_MODE_STABILIZED\020\r\022\031\n\025FLI" + "GHT_MODE_RATTITUDE\020\016*\371\001\n\016StatusTextType\022" + "\032\n\026STATUS_TEXT_TYPE_DEBUG\020\000\022\031\n\025STATUS_TE" + "XT_TYPE_INFO\020\001\022\033\n\027STATUS_TEXT_TYPE_NOTIC" + "E\020\002\022\034\n\030STATUS_TEXT_TYPE_WARNING\020\003\022\032\n\026STA" + "TUS_TEXT_TYPE_ERROR\020\004\022\035\n\031STATUS_TEXT_TYP" + "E_CRITICAL\020\005\022\032\n\026STATUS_TEXT_TYPE_ALERT\020\006" + "\022\036\n\032STATUS_TEXT_TYPE_EMERGENCY\020\007*\223\001\n\013Lan" + "dedState\022\030\n\024LANDED_STATE_UNKNOWN\020\000\022\032\n\026LA" + "NDED_STATE_ON_GROUND\020\001\022\027\n\023LANDED_STATE_I" + "N_AIR\020\002\022\033\n\027LANDED_STATE_TAKING_OFF\020\003\022\030\n\024" + "LANDED_STATE_LANDING\020\004*\215\001\n\tVtolState\022\030\n\024" + "VTOL_STATE_UNDEFINED\020\000\022\037\n\033VTOL_STATE_TRA" + "NSITION_TO_FW\020\001\022\037\n\033VTOL_STATE_TRANSITION" + "_TO_MC\020\002\022\021\n\rVTOL_STATE_MC\020\003\022\021\n\rVTOL_STAT" + "E_FW\020\0042\3075\n\020TelemetryService\022o\n\021Subscribe" + "Position\022..mavsdk.rpc.telemetry.Subscrib" + "ePositionRequest\032&.mavsdk.rpc.telemetry." + "PositionResponse\"\0000\001\022c\n\rSubscribeHome\022*." + "mavsdk.rpc.telemetry.SubscribeHomeReques" + "t\032\".mavsdk.rpc.telemetry.HomeResponse\"\0000" + "\001\022f\n\016SubscribeInAir\022+.mavsdk.rpc.telemet" + "ry.SubscribeInAirRequest\032#.mavsdk.rpc.te" + "lemetry.InAirResponse\"\0000\001\022x\n\024SubscribeLa" + "ndedState\0221.mavsdk.rpc.telemetry.Subscri" + "beLandedStateRequest\032).mavsdk.rpc.teleme" + "try.LandedStateResponse\"\0000\001\022f\n\016Subscribe" + "Armed\022+.mavsdk.rpc.telemetry.SubscribeAr" + "medRequest\032#.mavsdk.rpc.telemetry.ArmedR" + "esponse\"\0000\001\022r\n\022SubscribeVtolState\022/.mavs" + "dk.rpc.telemetry.SubscribeVtolStateReque" + "st\032\'.mavsdk.rpc.telemetry.VtolStateRespo" + "nse\"\0000\001\022\215\001\n\033SubscribeAttitudeQuaternion\022" + "8.mavsdk.rpc.telemetry.SubscribeAttitude" + "QuaternionRequest\0320.mavsdk.rpc.telemetry" + ".AttitudeQuaternionResponse\"\0000\001\022~\n\026Subsc" + "ribeAttitudeEuler\0223.mavsdk.rpc.telemetry" + ".SubscribeAttitudeEulerRequest\032+.mavsdk." + "rpc.telemetry.AttitudeEulerResponse\"\0000\001\022" + "\250\001\n$SubscribeAttitudeAngularVelocityBody" + "\022A.mavsdk.rpc.telemetry.SubscribeAttitud" + "eAngularVelocityBodyRequest\0329.mavsdk.rpc" + ".telemetry.AttitudeAngularVelocityBodyRe" + "sponse\"\0000\001\022x\n\024SubscribeVelocityNed\0221.mav" + "sdk.rpc.telemetry.SubscribeVelocityNedRe" + "quest\032).mavsdk.rpc.telemetry.VelocityNed" + "Response\"\0000\001\022l\n\020SubscribeGpsInfo\022-.mavsd" + "k.rpc.telemetry.SubscribeGpsInfoRequest\032" + "%.mavsdk.rpc.telemetry.GpsInfoResponse\"\000" + "0\001\022i\n\017SubscribeRawGps\022,.mavsdk.rpc.telem" + "etry.SubscribeRawGpsRequest\032$.mavsdk.rpc" + ".telemetry.RawGpsResponse\"\0000\001\022l\n\020Subscri" + "beBattery\022-.mavsdk.rpc.telemetry.Subscri" + "beBatteryRequest\032%.mavsdk.rpc.telemetry." + "BatteryResponse\"\0000\001\022u\n\023SubscribeFlightMo" + "de\0220.mavsdk.rpc.telemetry.SubscribeFligh" + "tModeRequest\032(.mavsdk.rpc.telemetry.Flig" + "htModeResponse\"\0000\001\022i\n\017SubscribeHealth\022,." + "mavsdk.rpc.telemetry.SubscribeHealthRequ" + "est\032$.mavsdk.rpc.telemetry.HealthRespons" + "e\"\0000\001\022o\n\021SubscribeRcStatus\022..mavsdk.rpc." + "telemetry.SubscribeRcStatusRequest\032&.mav" + "sdk.rpc.telemetry.RcStatusResponse\"\0000\001\022u" + "\n\023SubscribeStatusText\0220.mavsdk.rpc.telem" + "etry.SubscribeStatusTextRequest\032(.mavsdk" + ".rpc.telemetry.StatusTextResponse\"\0000\001\022\226\001" + "\n\036SubscribeActuatorControlTarget\022;.mavsd" + "k.rpc.telemetry.SubscribeActuatorControl" + "TargetRequest\0323.mavsdk.rpc.telemetry.Act" + "uatorControlTargetResponse\"\0000\001\022\223\001\n\035Subsc" + "ribeActuatorOutputStatus\022:.mavsdk.rpc.te" + "lemetry.SubscribeActuatorOutputStatusReq" + "uest\0322.mavsdk.rpc.telemetry.ActuatorOutp" + "utStatusResponse\"\0000\001\022o\n\021SubscribeOdometr" + "y\022..mavsdk.rpc.telemetry.SubscribeOdomet" + "ryRequest\032&.mavsdk.rpc.telemetry.Odometr" + "yResponse\"\0000\001\022\220\001\n\034SubscribePositionVeloc" + "ityNed\0229.mavsdk.rpc.telemetry.SubscribeP" + "ositionVelocityNedRequest\0321.mavsdk.rpc.t" + "elemetry.PositionVelocityNedResponse\"\0000\001" + "\022x\n\024SubscribeGroundTruth\0221.mavsdk.rpc.te" + "lemetry.SubscribeGroundTruthRequest\032).ma" + "vsdk.rpc.telemetry.GroundTruthResponse\"\000" + "0\001\022\207\001\n\031SubscribeFixedwingMetrics\0226.mavsd" + "k.rpc.telemetry.SubscribeFixedwingMetric" + "sRequest\032..mavsdk.rpc.telemetry.Fixedwin" + "gMetricsResponse\"\0000\001\022`\n\014SubscribeImu\022).m" + "avsdk.rpc.telemetry.SubscribeImuRequest\032" + "!.mavsdk.rpc.telemetry.ImuResponse\"\0000\001\022r" + "\n\022SubscribeScaledImu\022/.mavsdk.rpc.teleme" + "try.SubscribeScaledImuRequest\032\'.mavsdk.r" + "pc.telemetry.ScaledImuResponse\"\0000\001\022i\n\017Su" + "bscribeRawImu\022,.mavsdk.rpc.telemetry.Sub" + "scribeRawImuRequest\032$.mavsdk.rpc.telemet" + "ry.RawImuResponse\"\0000\001\022x\n\024SubscribeHealth" + "AllOk\0221.mavsdk.rpc.telemetry.SubscribeHe" + "althAllOkRequest\032).mavsdk.rpc.telemetry." + "HealthAllOkResponse\"\0000\001\022~\n\026SubscribeUnix" + "EpochTime\0223.mavsdk.rpc.telemetry.Subscri" + "beUnixEpochTimeRequest\032+.mavsdk.rpc.tele" + "metry.UnixEpochTimeResponse\"\0000\001\022\201\001\n\027Subs" + "cribeDistanceSensor\0224.mavsdk.rpc.telemet" + "ry.SubscribeDistanceSensorRequest\032,.mavs" + "dk.rpc.telemetry.DistanceSensorResponse\"" + "\0000\001\022\201\001\n\027SubscribeScaledPressure\0224.mavsdk" + ".rpc.telemetry.SubscribeScaledPressureRe" + "quest\032,.mavsdk.rpc.telemetry.ScaledPress" + "ureResponse\"\0000\001\022l\n\020SubscribeHeading\022-.ma" + "vsdk.rpc.telemetry.SubscribeHeadingReque" + "st\032%.mavsdk.rpc.telemetry.HeadingRespons" + "e\"\0000\001\022o\n\021SubscribeAltitude\022..mavsdk.rpc." + "telemetry.SubscribeAltitudeRequest\032&.mav" + "sdk.rpc.telemetry.AltitudeResponse\"\0000\001\022p" + "\n\017SetRatePosition\022,.mavsdk.rpc.telemetry" + ".SetRatePositionRequest\032-.mavsdk.rpc.tel" + "emetry.SetRatePositionResponse\"\000\022d\n\013SetR" + "ateHome\022(.mavsdk.rpc.telemetry.SetRateHo" + "meRequest\032).mavsdk.rpc.telemetry.SetRate" + "HomeResponse\"\000\022g\n\014SetRateInAir\022).mavsdk." + "rpc.telemetry.SetRateInAirRequest\032*.mavs" + "dk.rpc.telemetry.SetRateInAirResponse\"\000\022" + "y\n\022SetRateLandedState\022/.mavsdk.rpc.telem" + "etry.SetRateLandedStateRequest\0320.mavsdk." + "rpc.telemetry.SetRateLandedStateResponse" + "\"\000\022s\n\020SetRateVtolState\022-.mavsdk.rpc.tele" + "metry.SetRateVtolStateRequest\032..mavsdk.r" + "pc.telemetry.SetRateVtolStateResponse\"\000\022" + "\216\001\n\031SetRateAttitudeQuaternion\0226.mavsdk.r" + "pc.telemetry.SetRateAttitudeQuaternionRe" + "quest\0327.mavsdk.rpc.telemetry.SetRateAtti" + "tudeQuaternionResponse\"\000\022\177\n\024SetRateAttit" + "udeEuler\0221.mavsdk.rpc.telemetry.SetRateA" + "ttitudeEulerRequest\0322.mavsdk.rpc.telemet" + "ry.SetRateAttitudeEulerResponse\"\000\022y\n\022Set" + "RateVelocityNed\022/.mavsdk.rpc.telemetry.S" + "etRateVelocityNedRequest\0320.mavsdk.rpc.te" + "lemetry.SetRateVelocityNedResponse\"\000\022m\n\016" + "SetRateGpsInfo\022+.mavsdk.rpc.telemetry.Se" + "tRateGpsInfoRequest\032,.mavsdk.rpc.telemet" + "ry.SetRateGpsInfoResponse\"\000\022m\n\016SetRateBa" + "ttery\022+.mavsdk.rpc.telemetry.SetRateBatt" + "eryRequest\032,.mavsdk.rpc.telemetry.SetRat" + "eBatteryResponse\"\000\022p\n\017SetRateRcStatus\022,." + "mavsdk.rpc.telemetry.SetRateRcStatusRequ" + "est\032-.mavsdk.rpc.telemetry.SetRateRcStat" + "usResponse\"\000\022\227\001\n\034SetRateActuatorControlT" + "arget\0229.mavsdk.rpc.telemetry.SetRateActu" + "atorControlTargetRequest\032:.mavsdk.rpc.te" + "lemetry.SetRateActuatorControlTargetResp" + "onse\"\000\022\224\001\n\033SetRateActuatorOutputStatus\0228" + ".mavsdk.rpc.telemetry.SetRateActuatorOut" + "putStatusRequest\0329.mavsdk.rpc.telemetry." + "SetRateActuatorOutputStatusResponse\"\000\022p\n" + "\017SetRateOdometry\022,.mavsdk.rpc.telemetry." + "SetRateOdometryRequest\032-.mavsdk.rpc.tele" + "metry.SetRateOdometryResponse\"\000\022\221\001\n\032SetR" + "atePositionVelocityNed\0227.mavsdk.rpc.tele" + "metry.SetRatePositionVelocityNedRequest\032" + "8.mavsdk.rpc.telemetry.SetRatePositionVe" + "locityNedResponse\"\000\022y\n\022SetRateGroundTrut" + "h\022/.mavsdk.rpc.telemetry.SetRateGroundTr" + "uthRequest\0320.mavsdk.rpc.telemetry.SetRat" + "eGroundTruthResponse\"\000\022\210\001\n\027SetRateFixedw" + "ingMetrics\0224.mavsdk.rpc.telemetry.SetRat" + "eFixedwingMetricsRequest\0325.mavsdk.rpc.te" + "lemetry.SetRateFixedwingMetricsResponse\"" + "\000\022a\n\nSetRateImu\022\'.mavsdk.rpc.telemetry.S" + "etRateImuRequest\032(.mavsdk.rpc.telemetry." + "SetRateImuResponse\"\000\022s\n\020SetRateScaledImu" + "\022-.mavsdk.rpc.telemetry.SetRateScaledImu" + "Request\032..mavsdk.rpc.telemetry.SetRateSc" + "aledImuResponse\"\000\022j\n\rSetRateRawImu\022*.mav" + "sdk.rpc.telemetry.SetRateRawImuRequest\032+" + ".mavsdk.rpc.telemetry.SetRateRawImuRespo" + "nse\"\000\022\177\n\024SetRateUnixEpochTime\0221.mavsdk.r" + "pc.telemetry.SetRateUnixEpochTimeRequest" + "\0322.mavsdk.rpc.telemetry.SetRateUnixEpoch" + "TimeResponse\"\000\022\202\001\n\025SetRateDistanceSensor" + "\0222.mavsdk.rpc.telemetry.SetRateDistanceS" + "ensorRequest\0323.mavsdk.rpc.telemetry.SetR" + "ateDistanceSensorResponse\"\000\022p\n\017SetRateAl" + "titude\022,.mavsdk.rpc.telemetry.SetRateAlt" + "itudeRequest\032-.mavsdk.rpc.telemetry.SetR" + "ateAltitudeResponse\"\000\022y\n\022GetGpsGlobalOri" + "gin\022/.mavsdk.rpc.telemetry.GetGpsGlobalO" + "riginRequest\0320.mavsdk.rpc.telemetry.GetG" + "psGlobalOriginResponse\"\000B%\n\023io.mavsdk.te" + "lemetryB\016TelemetryProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_telemetry_2ftelemetry_2eproto_deps[1] = { @@ -5169,13 +4915,13 @@ static ::absl::once_flag descriptor_table_telemetry_2ftelemetry_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_telemetry_2ftelemetry_2eproto = { false, false, - 20858, + 19831, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", &descriptor_table_telemetry_2ftelemetry_2eproto_once, descriptor_table_telemetry_2ftelemetry_2eproto_deps, 1, - 154, + 146, schemas, file_default_instances, TableStruct_telemetry_2ftelemetry_2eproto::offsets, @@ -7327,24 +7073,24 @@ ::google::protobuf::Metadata AttitudeAngularVelocityBodyResponse::GetMetadata() } // =================================================================== -class SubscribeCameraAttitudeQuaternionRequest::_Internal { +class SubscribeVelocityNedRequest::_Internal { public: }; -SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena) +SubscribeVelocityNedRequest::SubscribeVelocityNedRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeVelocityNedRequest) } -SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest( +SubscribeVelocityNedRequest::SubscribeVelocityNedRequest( ::google::protobuf::Arena* arena, - const SubscribeCameraAttitudeQuaternionRequest& from) + const SubscribeVelocityNedRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeCameraAttitudeQuaternionRequest* const _this = this; + SubscribeVelocityNedRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeVelocityNedRequest) } @@ -7355,76 +7101,76 @@ SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionReque -::google::protobuf::Metadata SubscribeCameraAttitudeQuaternionRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeVelocityNedRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[18]); } // =================================================================== -class CameraAttitudeQuaternionResponse::_Internal { +class VelocityNedResponse::_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(CameraAttitudeQuaternionResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Quaternion& attitude_quaternion(const CameraAttitudeQuaternionResponse* msg); - static void set_has_attitude_quaternion(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::VelocityNed& velocity_ned(const VelocityNedResponse* msg); + static void set_has_velocity_ned(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::Quaternion& CameraAttitudeQuaternionResponse::_Internal::attitude_quaternion(const CameraAttitudeQuaternionResponse* msg) { - return *msg->_impl_.attitude_quaternion_; +const ::mavsdk::rpc::telemetry::VelocityNed& VelocityNedResponse::_Internal::velocity_ned(const VelocityNedResponse* msg) { + return *msg->_impl_.velocity_ned_; } -CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena) +VelocityNedResponse::VelocityNedResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.VelocityNedResponse) } -inline PROTOBUF_NDEBUG_INLINE CameraAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE VelocityNedResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse( +VelocityNedResponse::VelocityNedResponse( ::google::protobuf::Arena* arena, - const CameraAttitudeQuaternionResponse& from) + const VelocityNedResponse& from) : ::google::protobuf::Message(arena) { - CameraAttitudeQuaternionResponse* const _this = this; + VelocityNedResponse* 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_.attitude_quaternion_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Quaternion>(arena, *from._impl_.attitude_quaternion_) + _impl_.velocity_ned_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::VelocityNed>(arena, *from._impl_.velocity_ned_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.VelocityNedResponse) } -inline PROTOBUF_NDEBUG_INLINE CameraAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE VelocityNedResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void CameraAttitudeQuaternionResponse::SharedCtor(::_pb::Arena* arena) { +inline void VelocityNedResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.attitude_quaternion_ = {}; + _impl_.velocity_ned_ = {}; } -CameraAttitudeQuaternionResponse::~CameraAttitudeQuaternionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +VelocityNedResponse::~VelocityNedResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.VelocityNedResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void CameraAttitudeQuaternionResponse::SharedDtor() { +inline void VelocityNedResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.attitude_quaternion_; + delete _impl_.velocity_ned_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void CameraAttitudeQuaternionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +PROTOBUF_NOINLINE void VelocityNedResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.VelocityNedResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -7432,14 +7178,14 @@ PROTOBUF_NOINLINE void CameraAttitudeQuaternionResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.attitude_quaternion_ != nullptr); - _impl_.attitude_quaternion_->Clear(); + ABSL_DCHECK(_impl_.velocity_ned_ != nullptr); + _impl_.velocity_ned_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* CameraAttitudeQuaternionResponse::_InternalParse( +const char* VelocityNedResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -7447,9 +7193,9 @@ const char* CameraAttitudeQuaternionResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraAttitudeQuaternionResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> VelocityNedResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(CameraAttitudeQuaternionResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -7458,37 +7204,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraAttitudeQuaternionResponse::_tab 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_CameraAttitudeQuaternionResponse_default_instance_._instance, + &_VelocityNedResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(CameraAttitudeQuaternionResponse, _impl_.attitude_quaternion_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_.velocity_ned_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; - {PROTOBUF_FIELD_OFFSET(CameraAttitudeQuaternionResponse, _impl_.attitude_quaternion_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; + {PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_.velocity_ned_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Quaternion>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::VelocityNed>()}, }}, {{ }}, }; -::uint8_t* CameraAttitudeQuaternionResponse::_InternalSerialize( +::uint8_t* VelocityNedResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.VelocityNedResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::attitude_quaternion(this), - _Internal::attitude_quaternion(this).GetCachedSize(), target, stream); + 1, _Internal::velocity_ned(this), + _Internal::velocity_ned(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -7496,97 +7242,97 @@ ::uint8_t* CameraAttitudeQuaternionResponse::_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.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.VelocityNedResponse) return target; } -::size_t CameraAttitudeQuaternionResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +::size_t VelocityNedResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.VelocityNedResponse) ::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.telemetry.Quaternion attitude_quaternion = 1; + // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.attitude_quaternion_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.velocity_ned_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData CameraAttitudeQuaternionResponse::_class_data_ = { - CameraAttitudeQuaternionResponse::MergeImpl, +const ::google::protobuf::Message::ClassData VelocityNedResponse::_class_data_ = { + VelocityNedResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* CameraAttitudeQuaternionResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* VelocityNedResponse::GetClassData() const { return &_class_data_; } -void CameraAttitudeQuaternionResponse::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.telemetry.CameraAttitudeQuaternionResponse) +void VelocityNedResponse::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.telemetry.VelocityNedResponse) 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_attitude_quaternion()->::mavsdk::rpc::telemetry::Quaternion::MergeFrom( - from._internal_attitude_quaternion()); + _this->_internal_mutable_velocity_ned()->::mavsdk::rpc::telemetry::VelocityNed::MergeFrom( + from._internal_velocity_ned()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void CameraAttitudeQuaternionResponse::CopyFrom(const CameraAttitudeQuaternionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void VelocityNedResponse::CopyFrom(const VelocityNedResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.VelocityNedResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool CameraAttitudeQuaternionResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool VelocityNedResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* CameraAttitudeQuaternionResponse::AccessCachedSize() const { +::_pbi::CachedSize* VelocityNedResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void CameraAttitudeQuaternionResponse::InternalSwap(CameraAttitudeQuaternionResponse* PROTOBUF_RESTRICT other) { +void VelocityNedResponse::InternalSwap(VelocityNedResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.attitude_quaternion_, other->_impl_.attitude_quaternion_); + swap(_impl_.velocity_ned_, other->_impl_.velocity_ned_); } -::google::protobuf::Metadata CameraAttitudeQuaternionResponse::GetMetadata() const { +::google::protobuf::Metadata VelocityNedResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[19]); } // =================================================================== -class SubscribeCameraAttitudeEulerRequest::_Internal { +class SubscribeGpsInfoRequest::_Internal { public: }; -SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest(::google::protobuf::Arena* arena) +SubscribeGpsInfoRequest::SubscribeGpsInfoRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) } -SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest( +SubscribeGpsInfoRequest::SubscribeGpsInfoRequest( ::google::protobuf::Arena* arena, - const SubscribeCameraAttitudeEulerRequest& from) + const SubscribeGpsInfoRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeCameraAttitudeEulerRequest* const _this = this; + SubscribeGpsInfoRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) } @@ -7597,76 +7343,76 @@ SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest( -::google::protobuf::Metadata SubscribeCameraAttitudeEulerRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeGpsInfoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[20]); } // =================================================================== -class CameraAttitudeEulerResponse::_Internal { +class GpsInfoResponse::_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(CameraAttitudeEulerResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::EulerAngle& attitude_euler(const CameraAttitudeEulerResponse* msg); - static void set_has_attitude_euler(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::GpsInfo& gps_info(const GpsInfoResponse* msg); + static void set_has_gps_info(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::EulerAngle& CameraAttitudeEulerResponse::_Internal::attitude_euler(const CameraAttitudeEulerResponse* msg) { - return *msg->_impl_.attitude_euler_; +const ::mavsdk::rpc::telemetry::GpsInfo& GpsInfoResponse::_Internal::gps_info(const GpsInfoResponse* msg) { + return *msg->_impl_.gps_info_; } -CameraAttitudeEulerResponse::CameraAttitudeEulerResponse(::google::protobuf::Arena* arena) +GpsInfoResponse::GpsInfoResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE CameraAttitudeEulerResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GpsInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -CameraAttitudeEulerResponse::CameraAttitudeEulerResponse( +GpsInfoResponse::GpsInfoResponse( ::google::protobuf::Arena* arena, - const CameraAttitudeEulerResponse& from) + const GpsInfoResponse& from) : ::google::protobuf::Message(arena) { - CameraAttitudeEulerResponse* const _this = this; + GpsInfoResponse* 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_.attitude_euler_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::EulerAngle>(arena, *from._impl_.attitude_euler_) + _impl_.gps_info_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::GpsInfo>(arena, *from._impl_.gps_info_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) } -inline PROTOBUF_NDEBUG_INLINE CameraAttitudeEulerResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GpsInfoResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void CameraAttitudeEulerResponse::SharedCtor(::_pb::Arena* arena) { +inline void GpsInfoResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.attitude_euler_ = {}; + _impl_.gps_info_ = {}; } -CameraAttitudeEulerResponse::~CameraAttitudeEulerResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +GpsInfoResponse::~GpsInfoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfoResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void CameraAttitudeEulerResponse::SharedDtor() { +inline void GpsInfoResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.attitude_euler_; + delete _impl_.gps_info_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void CameraAttitudeEulerResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +PROTOBUF_NOINLINE void GpsInfoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfoResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -7674,14 +7420,14 @@ PROTOBUF_NOINLINE void CameraAttitudeEulerResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.attitude_euler_ != nullptr); - _impl_.attitude_euler_->Clear(); + ABSL_DCHECK(_impl_.gps_info_ != nullptr); + _impl_.gps_info_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* CameraAttitudeEulerResponse::_InternalParse( +const char* GpsInfoResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -7689,9 +7435,9 @@ const char* CameraAttitudeEulerResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraAttitudeEulerResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GpsInfoResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(CameraAttitudeEulerResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -7700,37 +7446,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> CameraAttitudeEulerResponse::_table_ = 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_CameraAttitudeEulerResponse_default_instance_._instance, + &_GpsInfoResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(CameraAttitudeEulerResponse, _impl_.attitude_euler_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_.gps_info_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; - {PROTOBUF_FIELD_OFFSET(CameraAttitudeEulerResponse, _impl_.attitude_euler_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + {PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_.gps_info_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::EulerAngle>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::GpsInfo>()}, }}, {{ }}, }; -::uint8_t* CameraAttitudeEulerResponse::_InternalSerialize( +::uint8_t* GpsInfoResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfoResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::attitude_euler(this), - _Internal::attitude_euler(this).GetCachedSize(), target, stream); + 1, _Internal::gps_info(this), + _Internal::gps_info(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -7738,97 +7484,97 @@ ::uint8_t* CameraAttitudeEulerResponse::_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.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GpsInfoResponse) return target; } -::size_t CameraAttitudeEulerResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +::size_t GpsInfoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfoResponse) ::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.telemetry.EulerAngle attitude_euler = 1; + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.attitude_euler_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.gps_info_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData CameraAttitudeEulerResponse::_class_data_ = { - CameraAttitudeEulerResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GpsInfoResponse::_class_data_ = { + GpsInfoResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* CameraAttitudeEulerResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GpsInfoResponse::GetClassData() const { return &_class_data_; } -void CameraAttitudeEulerResponse::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.telemetry.CameraAttitudeEulerResponse) +void GpsInfoResponse::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.telemetry.GpsInfoResponse) 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_attitude_euler()->::mavsdk::rpc::telemetry::EulerAngle::MergeFrom( - from._internal_attitude_euler()); + _this->_internal_mutable_gps_info()->::mavsdk::rpc::telemetry::GpsInfo::MergeFrom( + from._internal_gps_info()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void CameraAttitudeEulerResponse::CopyFrom(const CameraAttitudeEulerResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void GpsInfoResponse::CopyFrom(const GpsInfoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool CameraAttitudeEulerResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GpsInfoResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* CameraAttitudeEulerResponse::AccessCachedSize() const { +::_pbi::CachedSize* GpsInfoResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void CameraAttitudeEulerResponse::InternalSwap(CameraAttitudeEulerResponse* PROTOBUF_RESTRICT other) { +void GpsInfoResponse::InternalSwap(GpsInfoResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.attitude_euler_, other->_impl_.attitude_euler_); + swap(_impl_.gps_info_, other->_impl_.gps_info_); } -::google::protobuf::Metadata CameraAttitudeEulerResponse::GetMetadata() const { +::google::protobuf::Metadata GpsInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[21]); } // =================================================================== -class SubscribeVelocityNedRequest::_Internal { +class SubscribeRawGpsRequest::_Internal { public: }; -SubscribeVelocityNedRequest::SubscribeVelocityNedRequest(::google::protobuf::Arena* arena) +SubscribeRawGpsRequest::SubscribeRawGpsRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeVelocityNedRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRawGpsRequest) } -SubscribeVelocityNedRequest::SubscribeVelocityNedRequest( +SubscribeRawGpsRequest::SubscribeRawGpsRequest( ::google::protobuf::Arena* arena, - const SubscribeVelocityNedRequest& from) + const SubscribeRawGpsRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeVelocityNedRequest* const _this = this; + SubscribeRawGpsRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeVelocityNedRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRawGpsRequest) } @@ -7839,76 +7585,76 @@ SubscribeVelocityNedRequest::SubscribeVelocityNedRequest( -::google::protobuf::Metadata SubscribeVelocityNedRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeRawGpsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[22]); } // =================================================================== -class VelocityNedResponse::_Internal { +class RawGpsResponse::_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(VelocityNedResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::VelocityNed& velocity_ned(const VelocityNedResponse* msg); - static void set_has_velocity_ned(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::RawGps& raw_gps(const RawGpsResponse* msg); + static void set_has_raw_gps(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::VelocityNed& VelocityNedResponse::_Internal::velocity_ned(const VelocityNedResponse* msg) { - return *msg->_impl_.velocity_ned_; +const ::mavsdk::rpc::telemetry::RawGps& RawGpsResponse::_Internal::raw_gps(const RawGpsResponse* msg) { + return *msg->_impl_.raw_gps_; } -VelocityNedResponse::VelocityNedResponse(::google::protobuf::Arena* arena) +RawGpsResponse::RawGpsResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.VelocityNedResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RawGpsResponse) } -inline PROTOBUF_NDEBUG_INLINE VelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RawGpsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -VelocityNedResponse::VelocityNedResponse( +RawGpsResponse::RawGpsResponse( ::google::protobuf::Arena* arena, - const VelocityNedResponse& from) + const RawGpsResponse& from) : ::google::protobuf::Message(arena) { - VelocityNedResponse* const _this = this; + RawGpsResponse* 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_.velocity_ned_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::VelocityNed>(arena, *from._impl_.velocity_ned_) + _impl_.raw_gps_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::RawGps>(arena, *from._impl_.raw_gps_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.VelocityNedResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RawGpsResponse) } -inline PROTOBUF_NDEBUG_INLINE VelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RawGpsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void VelocityNedResponse::SharedCtor(::_pb::Arena* arena) { +inline void RawGpsResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.velocity_ned_ = {}; + _impl_.raw_gps_ = {}; } -VelocityNedResponse::~VelocityNedResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.VelocityNedResponse) +RawGpsResponse::~RawGpsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RawGpsResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void VelocityNedResponse::SharedDtor() { +inline void RawGpsResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.velocity_ned_; + delete _impl_.raw_gps_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void VelocityNedResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.VelocityNedResponse) +PROTOBUF_NOINLINE void RawGpsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RawGpsResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -7916,14 +7662,14 @@ PROTOBUF_NOINLINE void VelocityNedResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.velocity_ned_ != nullptr); - _impl_.velocity_ned_->Clear(); + ABSL_DCHECK(_impl_.raw_gps_ != nullptr); + _impl_.raw_gps_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* VelocityNedResponse::_InternalParse( +const char* RawGpsResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -7931,9 +7677,9 @@ const char* VelocityNedResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> VelocityNedResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RawGpsResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -7942,37 +7688,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> VelocityNedResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_VelocityNedResponse_default_instance_._instance, + &_RawGpsResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; + // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_.velocity_ned_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_.raw_gps_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; - {PROTOBUF_FIELD_OFFSET(VelocityNedResponse, _impl_.velocity_ned_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; + {PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_.raw_gps_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::VelocityNed>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::RawGps>()}, }}, {{ }}, }; -::uint8_t* VelocityNedResponse::_InternalSerialize( +::uint8_t* RawGpsResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.VelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RawGpsResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; + // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::velocity_ned(this), - _Internal::velocity_ned(this).GetCachedSize(), target, stream); + 1, _Internal::raw_gps(this), + _Internal::raw_gps(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -7980,97 +7726,97 @@ ::uint8_t* VelocityNedResponse::_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.telemetry.VelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RawGpsResponse) return target; } -::size_t VelocityNedResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.VelocityNedResponse) +::size_t RawGpsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RawGpsResponse) ::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.telemetry.VelocityNed velocity_ned = 1; + // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.velocity_ned_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.raw_gps_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData VelocityNedResponse::_class_data_ = { - VelocityNedResponse::MergeImpl, +const ::google::protobuf::Message::ClassData RawGpsResponse::_class_data_ = { + RawGpsResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* VelocityNedResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* RawGpsResponse::GetClassData() const { return &_class_data_; } -void VelocityNedResponse::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.telemetry.VelocityNedResponse) +void RawGpsResponse::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.telemetry.RawGpsResponse) 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_velocity_ned()->::mavsdk::rpc::telemetry::VelocityNed::MergeFrom( - from._internal_velocity_ned()); + _this->_internal_mutable_raw_gps()->::mavsdk::rpc::telemetry::RawGps::MergeFrom( + from._internal_raw_gps()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void VelocityNedResponse::CopyFrom(const VelocityNedResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.VelocityNedResponse) +void RawGpsResponse::CopyFrom(const RawGpsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RawGpsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool VelocityNedResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool RawGpsResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* VelocityNedResponse::AccessCachedSize() const { +::_pbi::CachedSize* RawGpsResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void VelocityNedResponse::InternalSwap(VelocityNedResponse* PROTOBUF_RESTRICT other) { +void RawGpsResponse::InternalSwap(RawGpsResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.velocity_ned_, other->_impl_.velocity_ned_); + swap(_impl_.raw_gps_, other->_impl_.raw_gps_); } -::google::protobuf::Metadata VelocityNedResponse::GetMetadata() const { +::google::protobuf::Metadata RawGpsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[23]); } // =================================================================== -class SubscribeGpsInfoRequest::_Internal { +class SubscribeBatteryRequest::_Internal { public: }; -SubscribeGpsInfoRequest::SubscribeGpsInfoRequest(::google::protobuf::Arena* arena) +SubscribeBatteryRequest::SubscribeBatteryRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) } -SubscribeGpsInfoRequest::SubscribeGpsInfoRequest( +SubscribeBatteryRequest::SubscribeBatteryRequest( ::google::protobuf::Arena* arena, - const SubscribeGpsInfoRequest& from) + const SubscribeBatteryRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeGpsInfoRequest* const _this = this; + SubscribeBatteryRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) } @@ -8081,76 +7827,76 @@ SubscribeGpsInfoRequest::SubscribeGpsInfoRequest( -::google::protobuf::Metadata SubscribeGpsInfoRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeBatteryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[24]); } // =================================================================== -class GpsInfoResponse::_Internal { +class BatteryResponse::_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(GpsInfoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::GpsInfo& gps_info(const GpsInfoResponse* msg); - static void set_has_gps_info(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Battery& battery(const BatteryResponse* msg); + static void set_has_battery(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::GpsInfo& GpsInfoResponse::_Internal::gps_info(const GpsInfoResponse* msg) { - return *msg->_impl_.gps_info_; +const ::mavsdk::rpc::telemetry::Battery& BatteryResponse::_Internal::battery(const BatteryResponse* msg) { + return *msg->_impl_.battery_; } -GpsInfoResponse::GpsInfoResponse(::google::protobuf::Arena* arena) +BatteryResponse::BatteryResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.BatteryResponse) } -inline PROTOBUF_NDEBUG_INLINE GpsInfoResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE BatteryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -GpsInfoResponse::GpsInfoResponse( +BatteryResponse::BatteryResponse( ::google::protobuf::Arena* arena, - const GpsInfoResponse& from) + const BatteryResponse& from) : ::google::protobuf::Message(arena) { - GpsInfoResponse* const _this = this; + BatteryResponse* 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_.gps_info_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::GpsInfo>(arena, *from._impl_.gps_info_) + _impl_.battery_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Battery>(arena, *from._impl_.battery_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.BatteryResponse) } -inline PROTOBUF_NDEBUG_INLINE GpsInfoResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE BatteryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void GpsInfoResponse::SharedCtor(::_pb::Arena* arena) { +inline void BatteryResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.gps_info_ = {}; + _impl_.battery_ = {}; } -GpsInfoResponse::~GpsInfoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfoResponse) +BatteryResponse::~BatteryResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.BatteryResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void GpsInfoResponse::SharedDtor() { +inline void BatteryResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.gps_info_; + delete _impl_.battery_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void GpsInfoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfoResponse) +PROTOBUF_NOINLINE void BatteryResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.BatteryResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8158,14 +7904,14 @@ PROTOBUF_NOINLINE void GpsInfoResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.gps_info_ != nullptr); - _impl_.gps_info_->Clear(); + ABSL_DCHECK(_impl_.battery_ != nullptr); + _impl_.battery_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* GpsInfoResponse::_InternalParse( +const char* BatteryResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8173,9 +7919,9 @@ const char* GpsInfoResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GpsInfoResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> BatteryResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8184,37 +7930,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GpsInfoResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_GpsInfoResponse_default_instance_._instance, + &_BatteryResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + // .mavsdk.rpc.telemetry.Battery battery = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_.gps_info_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_.battery_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; - {PROTOBUF_FIELD_OFFSET(GpsInfoResponse, _impl_.gps_info_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Battery battery = 1; + {PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_.battery_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::GpsInfo>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Battery>()}, }}, {{ }}, }; -::uint8_t* GpsInfoResponse::_InternalSerialize( +::uint8_t* BatteryResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.BatteryResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + // .mavsdk.rpc.telemetry.Battery battery = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::gps_info(this), - _Internal::gps_info(this).GetCachedSize(), target, stream); + 1, _Internal::battery(this), + _Internal::battery(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8222,97 +7968,97 @@ ::uint8_t* GpsInfoResponse::_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.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.BatteryResponse) return target; } -::size_t GpsInfoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfoResponse) +::size_t BatteryResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.BatteryResponse) ::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.telemetry.GpsInfo gps_info = 1; + // .mavsdk.rpc.telemetry.Battery battery = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.gps_info_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.battery_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData GpsInfoResponse::_class_data_ = { - GpsInfoResponse::MergeImpl, +const ::google::protobuf::Message::ClassData BatteryResponse::_class_data_ = { + BatteryResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* GpsInfoResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* BatteryResponse::GetClassData() const { return &_class_data_; } -void GpsInfoResponse::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.telemetry.GpsInfoResponse) +void BatteryResponse::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.telemetry.BatteryResponse) 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_gps_info()->::mavsdk::rpc::telemetry::GpsInfo::MergeFrom( - from._internal_gps_info()); + _this->_internal_mutable_battery()->::mavsdk::rpc::telemetry::Battery::MergeFrom( + from._internal_battery()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void GpsInfoResponse::CopyFrom(const GpsInfoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void BatteryResponse::CopyFrom(const BatteryResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool GpsInfoResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool BatteryResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* GpsInfoResponse::AccessCachedSize() const { +::_pbi::CachedSize* BatteryResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void GpsInfoResponse::InternalSwap(GpsInfoResponse* PROTOBUF_RESTRICT other) { +void BatteryResponse::InternalSwap(BatteryResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.gps_info_, other->_impl_.gps_info_); + swap(_impl_.battery_, other->_impl_.battery_); } -::google::protobuf::Metadata GpsInfoResponse::GetMetadata() const { +::google::protobuf::Metadata BatteryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[25]); } // =================================================================== -class SubscribeRawGpsRequest::_Internal { +class SubscribeFlightModeRequest::_Internal { public: }; -SubscribeRawGpsRequest::SubscribeRawGpsRequest(::google::protobuf::Arena* arena) +SubscribeFlightModeRequest::SubscribeFlightModeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRawGpsRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) } -SubscribeRawGpsRequest::SubscribeRawGpsRequest( +SubscribeFlightModeRequest::SubscribeFlightModeRequest( ::google::protobuf::Arena* arena, - const SubscribeRawGpsRequest& from) + const SubscribeFlightModeRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeRawGpsRequest* const _this = this; + SubscribeFlightModeRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRawGpsRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) } @@ -8323,91 +8069,58 @@ SubscribeRawGpsRequest::SubscribeRawGpsRequest( -::google::protobuf::Metadata SubscribeRawGpsRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeFlightModeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[26]); } // =================================================================== -class RawGpsResponse::_Internal { +class FlightModeResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::RawGps& raw_gps(const RawGpsResponse* msg); - static void set_has_raw_gps(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::telemetry::RawGps& RawGpsResponse::_Internal::raw_gps(const RawGpsResponse* msg) { - return *msg->_impl_.raw_gps_; -} -RawGpsResponse::RawGpsResponse(::google::protobuf::Arena* arena) +FlightModeResponse::FlightModeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RawGpsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.FlightModeResponse) } -inline PROTOBUF_NDEBUG_INLINE RawGpsResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -RawGpsResponse::RawGpsResponse( - ::google::protobuf::Arena* arena, - const RawGpsResponse& from) - : ::google::protobuf::Message(arena) { - RawGpsResponse* 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_.raw_gps_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::RawGps>(arena, *from._impl_.raw_gps_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RawGpsResponse) +FlightModeResponse::FlightModeResponse( + ::google::protobuf::Arena* arena, const FlightModeResponse& from) + : FlightModeResponse(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE RawGpsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FlightModeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RawGpsResponse::SharedCtor(::_pb::Arena* arena) { +inline void FlightModeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.raw_gps_ = {}; + _impl_.flight_mode_ = {}; } -RawGpsResponse::~RawGpsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RawGpsResponse) +FlightModeResponse::~FlightModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FlightModeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RawGpsResponse::SharedDtor() { +inline void FlightModeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.raw_gps_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RawGpsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RawGpsResponse) +PROTOBUF_NOINLINE void FlightModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FlightModeResponse) 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_.raw_gps_ != nullptr); - _impl_.raw_gps_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.flight_mode_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RawGpsResponse::_InternalParse( +const char* FlightModeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8415,48 +8128,47 @@ const char* RawGpsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RawGpsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FlightModeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_RawGpsResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_FlightModeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_.raw_gps_)}}, + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FlightModeResponse, _impl_.flight_mode_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(FlightModeResponse, _impl_.flight_mode_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; - {PROTOBUF_FIELD_OFFSET(RawGpsResponse, _impl_.raw_gps_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::RawGps>()}, - }}, {{ + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + {PROTOBUF_FIELD_OFFSET(FlightModeResponse, _impl_.flight_mode_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* RawGpsResponse::_InternalSerialize( +::uint8_t* FlightModeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RawGpsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FlightModeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::raw_gps(this), - _Internal::raw_gps(this).GetCachedSize(), target, stream); + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + if (this->_internal_flight_mode() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteEnumToArray( + 1, this->_internal_flight_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8464,97 +8176,94 @@ ::uint8_t* RawGpsResponse::_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.telemetry.RawGpsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.FlightModeResponse) return target; } -::size_t RawGpsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RawGpsResponse) +::size_t FlightModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FlightModeResponse) ::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.telemetry.RawGps raw_gps = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.raw_gps_); + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + if (this->_internal_flight_mode() != 0) { + total_size += 1 + + ::_pbi::WireFormatLite::EnumSize(this->_internal_flight_mode()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RawGpsResponse::_class_data_ = { - RawGpsResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FlightModeResponse::_class_data_ = { + FlightModeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RawGpsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FlightModeResponse::GetClassData() const { return &_class_data_; } -void RawGpsResponse::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.telemetry.RawGpsResponse) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; +void FlightModeResponse::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.telemetry.FlightModeResponse) + 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_raw_gps()->::mavsdk::rpc::telemetry::RawGps::MergeFrom( - from._internal_raw_gps()); + if (from._internal_flight_mode() != 0) { + _this->_internal_set_flight_mode(from._internal_flight_mode()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RawGpsResponse::CopyFrom(const RawGpsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RawGpsResponse) +void FlightModeResponse::CopyFrom(const FlightModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RawGpsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FlightModeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* RawGpsResponse::AccessCachedSize() const { +::_pbi::CachedSize* FlightModeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void RawGpsResponse::InternalSwap(RawGpsResponse* PROTOBUF_RESTRICT other) { +void FlightModeResponse::InternalSwap(FlightModeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.raw_gps_, other->_impl_.raw_gps_); + swap(_impl_.flight_mode_, other->_impl_.flight_mode_); } -::google::protobuf::Metadata RawGpsResponse::GetMetadata() const { +::google::protobuf::Metadata FlightModeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[27]); } // =================================================================== -class SubscribeBatteryRequest::_Internal { +class SubscribeHealthRequest::_Internal { public: }; -SubscribeBatteryRequest::SubscribeBatteryRequest(::google::protobuf::Arena* arena) +SubscribeHealthRequest::SubscribeHealthRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) } -SubscribeBatteryRequest::SubscribeBatteryRequest( +SubscribeHealthRequest::SubscribeHealthRequest( ::google::protobuf::Arena* arena, - const SubscribeBatteryRequest& from) + const SubscribeHealthRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeBatteryRequest* const _this = this; + SubscribeHealthRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) } @@ -8565,76 +8274,76 @@ SubscribeBatteryRequest::SubscribeBatteryRequest( -::google::protobuf::Metadata SubscribeBatteryRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeHealthRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[28]); } // =================================================================== -class BatteryResponse::_Internal { +class HealthResponse::_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(BatteryResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Battery& battery(const BatteryResponse* msg); - static void set_has_battery(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Health& health(const HealthResponse* msg); + static void set_has_health(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::Battery& BatteryResponse::_Internal::battery(const BatteryResponse* msg) { - return *msg->_impl_.battery_; +const ::mavsdk::rpc::telemetry::Health& HealthResponse::_Internal::health(const HealthResponse* msg) { + return *msg->_impl_.health_; } -BatteryResponse::BatteryResponse(::google::protobuf::Arena* arena) +HealthResponse::HealthResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HealthResponse) } -inline PROTOBUF_NDEBUG_INLINE BatteryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE HealthResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -BatteryResponse::BatteryResponse( +HealthResponse::HealthResponse( ::google::protobuf::Arena* arena, - const BatteryResponse& from) + const HealthResponse& from) : ::google::protobuf::Message(arena) { - BatteryResponse* const _this = this; + HealthResponse* 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_.battery_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Battery>(arena, *from._impl_.battery_) + _impl_.health_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Health>(arena, *from._impl_.health_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HealthResponse) } -inline PROTOBUF_NDEBUG_INLINE BatteryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE HealthResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void BatteryResponse::SharedCtor(::_pb::Arena* arena) { +inline void HealthResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.battery_ = {}; + _impl_.health_ = {}; } -BatteryResponse::~BatteryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.BatteryResponse) +HealthResponse::~HealthResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void BatteryResponse::SharedDtor() { +inline void HealthResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.battery_; + delete _impl_.health_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void BatteryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.BatteryResponse) +PROTOBUF_NOINLINE void HealthResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8642,14 +8351,14 @@ PROTOBUF_NOINLINE void BatteryResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.battery_ != nullptr); - _impl_.battery_->Clear(); + ABSL_DCHECK(_impl_.health_ != nullptr); + _impl_.health_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* BatteryResponse::_InternalParse( +const char* HealthResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8657,9 +8366,9 @@ const char* BatteryResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> BatteryResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> HealthResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8668,37 +8377,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> BatteryResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_BatteryResponse_default_instance_._instance, + &_HealthResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Battery battery = 1; + // .mavsdk.rpc.telemetry.Health health = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_.battery_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_.health_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Battery battery = 1; - {PROTOBUF_FIELD_OFFSET(BatteryResponse, _impl_.battery_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Health health = 1; + {PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_.health_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Battery>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Health>()}, }}, {{ }}, }; -::uint8_t* BatteryResponse::_InternalSerialize( +::uint8_t* HealthResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Battery battery = 1; + // .mavsdk.rpc.telemetry.Health health = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::battery(this), - _Internal::battery(this).GetCachedSize(), target, stream); + 1, _Internal::health(this), + _Internal::health(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8706,97 +8415,97 @@ ::uint8_t* BatteryResponse::_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.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.HealthResponse) return target; } -::size_t BatteryResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.BatteryResponse) +::size_t HealthResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthResponse) ::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.telemetry.Battery battery = 1; + // .mavsdk.rpc.telemetry.Health health = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.battery_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.health_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData BatteryResponse::_class_data_ = { - BatteryResponse::MergeImpl, +const ::google::protobuf::Message::ClassData HealthResponse::_class_data_ = { + HealthResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* BatteryResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* HealthResponse::GetClassData() const { return &_class_data_; } -void BatteryResponse::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.telemetry.BatteryResponse) +void HealthResponse::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.telemetry.HealthResponse) 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_battery()->::mavsdk::rpc::telemetry::Battery::MergeFrom( - from._internal_battery()); + _this->_internal_mutable_health()->::mavsdk::rpc::telemetry::Health::MergeFrom( + from._internal_health()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void BatteryResponse::CopyFrom(const BatteryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) +void HealthResponse::CopyFrom(const HealthResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool BatteryResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool HealthResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* BatteryResponse::AccessCachedSize() const { +::_pbi::CachedSize* HealthResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void BatteryResponse::InternalSwap(BatteryResponse* PROTOBUF_RESTRICT other) { +void HealthResponse::InternalSwap(HealthResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.battery_, other->_impl_.battery_); + swap(_impl_.health_, other->_impl_.health_); } -::google::protobuf::Metadata BatteryResponse::GetMetadata() const { +::google::protobuf::Metadata HealthResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[29]); } // =================================================================== -class SubscribeFlightModeRequest::_Internal { +class SubscribeRcStatusRequest::_Internal { public: }; -SubscribeFlightModeRequest::SubscribeFlightModeRequest(::google::protobuf::Arena* arena) +SubscribeRcStatusRequest::SubscribeRcStatusRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) } -SubscribeFlightModeRequest::SubscribeFlightModeRequest( +SubscribeRcStatusRequest::SubscribeRcStatusRequest( ::google::protobuf::Arena* arena, - const SubscribeFlightModeRequest& from) + const SubscribeRcStatusRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeFlightModeRequest* const _this = this; + SubscribeRcStatusRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) } @@ -8807,58 +8516,91 @@ SubscribeFlightModeRequest::SubscribeFlightModeRequest( -::google::protobuf::Metadata SubscribeFlightModeRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeRcStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[30]); } // =================================================================== -class FlightModeResponse::_Internal { +class RcStatusResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::RcStatus& rc_status(const RcStatusResponse* msg); + static void set_has_rc_status(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -FlightModeResponse::FlightModeResponse(::google::protobuf::Arena* arena) +const ::mavsdk::rpc::telemetry::RcStatus& RcStatusResponse::_Internal::rc_status(const RcStatusResponse* msg) { + return *msg->_impl_.rc_status_; +} +RcStatusResponse::RcStatusResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RcStatusResponse) } -FlightModeResponse::FlightModeResponse( - ::google::protobuf::Arena* arena, const FlightModeResponse& from) - : FlightModeResponse(arena) { - MergeFrom(from); +inline PROTOBUF_NDEBUG_INLINE RcStatusResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +RcStatusResponse::RcStatusResponse( + ::google::protobuf::Arena* arena, + const RcStatusResponse& from) + : ::google::protobuf::Message(arena) { + RcStatusResponse* 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_.rc_status_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::RcStatus>(arena, *from._impl_.rc_status_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE FlightModeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RcStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void FlightModeResponse::SharedCtor(::_pb::Arena* arena) { +inline void RcStatusResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.flight_mode_ = {}; + _impl_.rc_status_ = {}; } -FlightModeResponse::~FlightModeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FlightModeResponse) +RcStatusResponse::~RcStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatusResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FlightModeResponse::SharedDtor() { +inline void RcStatusResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.rc_status_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void FlightModeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FlightModeResponse) +PROTOBUF_NOINLINE void RcStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatusResponse) 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_.flight_mode_ = 0; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.rc_status_ != nullptr); + _impl_.rc_status_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FlightModeResponse::_InternalParse( +const char* RcStatusResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -8866,47 +8608,48 @@ const char* FlightModeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> FlightModeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RcStatusResponse::_table_ = { { - 0, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(RcStatusResponse, _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 - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_FlightModeResponse_default_instance_._instance, + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_RcStatusResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(FlightModeResponse, _impl_.flight_mode_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(FlightModeResponse, _impl_.flight_mode_)}}, + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_.rc_status_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - {PROTOBUF_FIELD_OFFSET(FlightModeResponse, _impl_.flight_mode_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - }}, - // no aux_entries - {{ + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + {PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_.rc_status_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::RcStatus>()}, + }}, {{ }}, }; -::uint8_t* FlightModeResponse::_InternalSerialize( +::uint8_t* RcStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - if (this->_internal_flight_mode() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_flight_mode(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::rc_status(this), + _Internal::rc_status(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -8914,94 +8657,97 @@ ::uint8_t* FlightModeResponse::_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.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RcStatusResponse) return target; } -::size_t FlightModeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FlightModeResponse) +::size_t RcStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatusResponse) ::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.telemetry.FlightMode flight_mode = 1; - if (this->_internal_flight_mode() != 0) { - total_size += 1 + - ::_pbi::WireFormatLite::EnumSize(this->_internal_flight_mode()); + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.rc_status_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FlightModeResponse::_class_data_ = { - FlightModeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData RcStatusResponse::_class_data_ = { + RcStatusResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FlightModeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* RcStatusResponse::GetClassData() const { return &_class_data_; } -void FlightModeResponse::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.telemetry.FlightModeResponse) +void RcStatusResponse::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.telemetry.RcStatusResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_flight_mode() != 0) { - _this->_internal_set_flight_mode(from._internal_flight_mode()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_rc_status()->::mavsdk::rpc::telemetry::RcStatus::MergeFrom( + from._internal_rc_status()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void FlightModeResponse::CopyFrom(const FlightModeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) +void RcStatusResponse::CopyFrom(const RcStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FlightModeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool RcStatusResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* FlightModeResponse::AccessCachedSize() const { +::_pbi::CachedSize* RcStatusResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void FlightModeResponse::InternalSwap(FlightModeResponse* PROTOBUF_RESTRICT other) { +void RcStatusResponse::InternalSwap(RcStatusResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.flight_mode_, other->_impl_.flight_mode_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.rc_status_, other->_impl_.rc_status_); } -::google::protobuf::Metadata FlightModeResponse::GetMetadata() const { +::google::protobuf::Metadata RcStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[31]); } // =================================================================== -class SubscribeHealthRequest::_Internal { +class SubscribeStatusTextRequest::_Internal { public: }; -SubscribeHealthRequest::SubscribeHealthRequest(::google::protobuf::Arena* arena) +SubscribeStatusTextRequest::SubscribeStatusTextRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) } -SubscribeHealthRequest::SubscribeHealthRequest( +SubscribeStatusTextRequest::SubscribeStatusTextRequest( ::google::protobuf::Arena* arena, - const SubscribeHealthRequest& from) + const SubscribeStatusTextRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeHealthRequest* const _this = this; + SubscribeStatusTextRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) } @@ -9012,76 +8758,76 @@ SubscribeHealthRequest::SubscribeHealthRequest( -::google::protobuf::Metadata SubscribeHealthRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeStatusTextRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[32]); } // =================================================================== -class HealthResponse::_Internal { +class StatusTextResponse::_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(HealthResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Health& health(const HealthResponse* msg); - static void set_has_health(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::StatusText& status_text(const StatusTextResponse* msg); + static void set_has_status_text(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::Health& HealthResponse::_Internal::health(const HealthResponse* msg) { - return *msg->_impl_.health_; +const ::mavsdk::rpc::telemetry::StatusText& StatusTextResponse::_Internal::status_text(const StatusTextResponse* msg) { + return *msg->_impl_.status_text_; } -HealthResponse::HealthResponse(::google::protobuf::Arena* arena) +StatusTextResponse::StatusTextResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.StatusTextResponse) } -inline PROTOBUF_NDEBUG_INLINE HealthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE StatusTextResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -HealthResponse::HealthResponse( +StatusTextResponse::StatusTextResponse( ::google::protobuf::Arena* arena, - const HealthResponse& from) + const StatusTextResponse& from) : ::google::protobuf::Message(arena) { - HealthResponse* const _this = this; + StatusTextResponse* 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_.health_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Health>(arena, *from._impl_.health_) + _impl_.status_text_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::StatusText>(arena, *from._impl_.status_text_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusTextResponse) } -inline PROTOBUF_NDEBUG_INLINE HealthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE StatusTextResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void HealthResponse::SharedCtor(::_pb::Arena* arena) { +inline void StatusTextResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.health_ = {}; + _impl_.status_text_ = {}; } -HealthResponse::~HealthResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthResponse) +StatusTextResponse::~StatusTextResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusTextResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void HealthResponse::SharedDtor() { +inline void StatusTextResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.health_; + delete _impl_.status_text_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void HealthResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthResponse) +PROTOBUF_NOINLINE void StatusTextResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusTextResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9089,14 +8835,14 @@ PROTOBUF_NOINLINE void HealthResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.health_ != nullptr); - _impl_.health_->Clear(); + ABSL_DCHECK(_impl_.status_text_ != nullptr); + _impl_.status_text_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* HealthResponse::_InternalParse( +const char* StatusTextResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9104,9 +8850,9 @@ const char* HealthResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> HealthResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> StatusTextResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9115,37 +8861,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> HealthResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_HealthResponse_default_instance_._instance, + &_StatusTextResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Health health = 1; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_.health_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_.status_text_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Health health = 1; - {PROTOBUF_FIELD_OFFSET(HealthResponse, _impl_.health_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.StatusText status_text = 1; + {PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_.status_text_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Health>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::StatusText>()}, }}, {{ }}, }; -::uint8_t* HealthResponse::_InternalSerialize( +::uint8_t* StatusTextResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusTextResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Health health = 1; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::health(this), - _Internal::health(this).GetCachedSize(), target, stream); + 1, _Internal::status_text(this), + _Internal::status_text(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9153,97 +8899,97 @@ ::uint8_t* HealthResponse::_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.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.StatusTextResponse) return target; } -::size_t HealthResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthResponse) +::size_t StatusTextResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusTextResponse) ::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.telemetry.Health health = 1; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.health_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.status_text_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData HealthResponse::_class_data_ = { - HealthResponse::MergeImpl, +const ::google::protobuf::Message::ClassData StatusTextResponse::_class_data_ = { + StatusTextResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* HealthResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* StatusTextResponse::GetClassData() const { return &_class_data_; } -void HealthResponse::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.telemetry.HealthResponse) +void StatusTextResponse::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.telemetry.StatusTextResponse) 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_health()->::mavsdk::rpc::telemetry::Health::MergeFrom( - from._internal_health()); + _this->_internal_mutable_status_text()->::mavsdk::rpc::telemetry::StatusText::MergeFrom( + from._internal_status_text()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void HealthResponse::CopyFrom(const HealthResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) +void StatusTextResponse::CopyFrom(const StatusTextResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool HealthResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool StatusTextResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* HealthResponse::AccessCachedSize() const { +::_pbi::CachedSize* StatusTextResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void HealthResponse::InternalSwap(HealthResponse* PROTOBUF_RESTRICT other) { +void StatusTextResponse::InternalSwap(StatusTextResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.health_, other->_impl_.health_); + swap(_impl_.status_text_, other->_impl_.status_text_); } -::google::protobuf::Metadata HealthResponse::GetMetadata() const { +::google::protobuf::Metadata StatusTextResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[33]); } // =================================================================== -class SubscribeRcStatusRequest::_Internal { +class SubscribeActuatorControlTargetRequest::_Internal { public: }; -SubscribeRcStatusRequest::SubscribeRcStatusRequest(::google::protobuf::Arena* arena) +SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) } -SubscribeRcStatusRequest::SubscribeRcStatusRequest( +SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest( ::google::protobuf::Arena* arena, - const SubscribeRcStatusRequest& from) + const SubscribeActuatorControlTargetRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeRcStatusRequest* const _this = this; + SubscribeActuatorControlTargetRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) } @@ -9254,76 +9000,76 @@ SubscribeRcStatusRequest::SubscribeRcStatusRequest( -::google::protobuf::Metadata SubscribeRcStatusRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeActuatorControlTargetRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[34]); } // =================================================================== -class RcStatusResponse::_Internal { +class ActuatorControlTargetResponse::_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(RcStatusResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::RcStatus& rc_status(const RcStatusResponse* msg); - static void set_has_rc_status(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::ActuatorControlTarget& actuator_control_target(const ActuatorControlTargetResponse* msg); + static void set_has_actuator_control_target(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::RcStatus& RcStatusResponse::_Internal::rc_status(const RcStatusResponse* msg) { - return *msg->_impl_.rc_status_; +const ::mavsdk::rpc::telemetry::ActuatorControlTarget& ActuatorControlTargetResponse::_Internal::actuator_control_target(const ActuatorControlTargetResponse* msg) { + return *msg->_impl_.actuator_control_target_; } -RcStatusResponse::RcStatusResponse(::google::protobuf::Arena* arena) +ActuatorControlTargetResponse::ActuatorControlTargetResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) } -inline PROTOBUF_NDEBUG_INLINE RcStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ActuatorControlTargetResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -RcStatusResponse::RcStatusResponse( +ActuatorControlTargetResponse::ActuatorControlTargetResponse( ::google::protobuf::Arena* arena, - const RcStatusResponse& from) + const ActuatorControlTargetResponse& from) : ::google::protobuf::Message(arena) { - RcStatusResponse* const _this = this; + ActuatorControlTargetResponse* 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_.rc_status_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::RcStatus>(arena, *from._impl_.rc_status_) + _impl_.actuator_control_target_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTarget>(arena, *from._impl_.actuator_control_target_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) } -inline PROTOBUF_NDEBUG_INLINE RcStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ActuatorControlTargetResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RcStatusResponse::SharedCtor(::_pb::Arena* arena) { +inline void ActuatorControlTargetResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.rc_status_ = {}; + _impl_.actuator_control_target_ = {}; } -RcStatusResponse::~RcStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatusResponse) +ActuatorControlTargetResponse::~ActuatorControlTargetResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RcStatusResponse::SharedDtor() { +inline void ActuatorControlTargetResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.rc_status_; + delete _impl_.actuator_control_target_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RcStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatusResponse) +PROTOBUF_NOINLINE void ActuatorControlTargetResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9331,14 +9077,14 @@ PROTOBUF_NOINLINE void RcStatusResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.rc_status_ != nullptr); - _impl_.rc_status_->Clear(); + ABSL_DCHECK(_impl_.actuator_control_target_ != nullptr); + _impl_.actuator_control_target_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RcStatusResponse::_InternalParse( +const char* ActuatorControlTargetResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9346,9 +9092,9 @@ const char* RcStatusResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RcStatusResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorControlTargetResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9357,37 +9103,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RcStatusResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_RcStatusResponse_default_instance_._instance, + &_ActuatorControlTargetResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_.rc_status_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_.actuator_control_target_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; - {PROTOBUF_FIELD_OFFSET(RcStatusResponse, _impl_.rc_status_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + {PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_.actuator_control_target_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::RcStatus>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ActuatorControlTarget>()}, }}, {{ }}, }; -::uint8_t* RcStatusResponse::_InternalSerialize( +::uint8_t* ActuatorControlTargetResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::rc_status(this), - _Internal::rc_status(this).GetCachedSize(), target, stream); + 1, _Internal::actuator_control_target(this), + _Internal::actuator_control_target(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9395,97 +9141,97 @@ ::uint8_t* RcStatusResponse::_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.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) return target; } -::size_t RcStatusResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatusResponse) +::size_t ActuatorControlTargetResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::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.telemetry.RcStatus rc_status = 1; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.rc_status_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.actuator_control_target_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RcStatusResponse::_class_data_ = { - RcStatusResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ActuatorControlTargetResponse::_class_data_ = { + ActuatorControlTargetResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RcStatusResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ActuatorControlTargetResponse::GetClassData() const { return &_class_data_; } -void RcStatusResponse::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.telemetry.RcStatusResponse) +void ActuatorControlTargetResponse::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.telemetry.ActuatorControlTargetResponse) 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_rc_status()->::mavsdk::rpc::telemetry::RcStatus::MergeFrom( - from._internal_rc_status()); + _this->_internal_mutable_actuator_control_target()->::mavsdk::rpc::telemetry::ActuatorControlTarget::MergeFrom( + from._internal_actuator_control_target()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RcStatusResponse::CopyFrom(const RcStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) +void ActuatorControlTargetResponse::CopyFrom(const ActuatorControlTargetResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RcStatusResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ActuatorControlTargetResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* RcStatusResponse::AccessCachedSize() const { +::_pbi::CachedSize* ActuatorControlTargetResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void RcStatusResponse::InternalSwap(RcStatusResponse* PROTOBUF_RESTRICT other) { +void ActuatorControlTargetResponse::InternalSwap(ActuatorControlTargetResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.rc_status_, other->_impl_.rc_status_); + swap(_impl_.actuator_control_target_, other->_impl_.actuator_control_target_); } -::google::protobuf::Metadata RcStatusResponse::GetMetadata() const { +::google::protobuf::Metadata ActuatorControlTargetResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[35]); } // =================================================================== -class SubscribeStatusTextRequest::_Internal { +class SubscribeActuatorOutputStatusRequest::_Internal { public: }; -SubscribeStatusTextRequest::SubscribeStatusTextRequest(::google::protobuf::Arena* arena) +SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) } -SubscribeStatusTextRequest::SubscribeStatusTextRequest( +SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest( ::google::protobuf::Arena* arena, - const SubscribeStatusTextRequest& from) + const SubscribeActuatorOutputStatusRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeStatusTextRequest* const _this = this; + SubscribeActuatorOutputStatusRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) } @@ -9496,76 +9242,76 @@ SubscribeStatusTextRequest::SubscribeStatusTextRequest( -::google::protobuf::Metadata SubscribeStatusTextRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeActuatorOutputStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[36]); } // =================================================================== -class StatusTextResponse::_Internal { +class ActuatorOutputStatusResponse::_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(StatusTextResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::StatusText& status_text(const StatusTextResponse* msg); - static void set_has_status_text(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& actuator_output_status(const ActuatorOutputStatusResponse* msg); + static void set_has_actuator_output_status(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::StatusText& StatusTextResponse::_Internal::status_text(const StatusTextResponse* msg) { - return *msg->_impl_.status_text_; +const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& ActuatorOutputStatusResponse::_Internal::actuator_output_status(const ActuatorOutputStatusResponse* msg) { + return *msg->_impl_.actuator_output_status_; } -StatusTextResponse::StatusTextResponse(::google::protobuf::Arena* arena) +ActuatorOutputStatusResponse::ActuatorOutputStatusResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE StatusTextResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ActuatorOutputStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -StatusTextResponse::StatusTextResponse( +ActuatorOutputStatusResponse::ActuatorOutputStatusResponse( ::google::protobuf::Arena* arena, - const StatusTextResponse& from) + const ActuatorOutputStatusResponse& from) : ::google::protobuf::Message(arena) { - StatusTextResponse* const _this = this; + ActuatorOutputStatusResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.status_text_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::StatusText>(arena, *from._impl_.status_text_) + _impl_.actuator_output_status_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatus>(arena, *from._impl_.actuator_output_status_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE StatusTextResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ActuatorOutputStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void StatusTextResponse::SharedCtor(::_pb::Arena* arena) { +inline void ActuatorOutputStatusResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.status_text_ = {}; + _impl_.actuator_output_status_ = {}; } -StatusTextResponse::~StatusTextResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusTextResponse) +ActuatorOutputStatusResponse::~ActuatorOutputStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void StatusTextResponse::SharedDtor() { +inline void ActuatorOutputStatusResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.status_text_; + delete _impl_.actuator_output_status_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void StatusTextResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusTextResponse) +PROTOBUF_NOINLINE void ActuatorOutputStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9573,14 +9319,14 @@ PROTOBUF_NOINLINE void StatusTextResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.status_text_ != nullptr); - _impl_.status_text_->Clear(); + ABSL_DCHECK(_impl_.actuator_output_status_ != nullptr); + _impl_.actuator_output_status_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* StatusTextResponse::_InternalParse( +const char* ActuatorOutputStatusResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9588,9 +9334,9 @@ const char* StatusTextResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> StatusTextResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorOutputStatusResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9599,37 +9345,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> StatusTextResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_StatusTextResponse_default_instance_._instance, + &_ActuatorOutputStatusResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.StatusText status_text = 1; + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_.status_text_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_.actuator_output_status_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.StatusText status_text = 1; - {PROTOBUF_FIELD_OFFSET(StatusTextResponse, _impl_.status_text_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + {PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_.actuator_output_status_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::StatusText>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ActuatorOutputStatus>()}, }}, {{ }}, }; -::uint8_t* StatusTextResponse::_InternalSerialize( +::uint8_t* ActuatorOutputStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.StatusText status_text = 1; + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::status_text(this), - _Internal::status_text(this).GetCachedSize(), target, stream); + 1, _Internal::actuator_output_status(this), + _Internal::actuator_output_status(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9637,97 +9383,97 @@ ::uint8_t* StatusTextResponse::_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.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) return target; } -::size_t StatusTextResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusTextResponse) +::size_t ActuatorOutputStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) ::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.telemetry.StatusText status_text = 1; + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.status_text_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.actuator_output_status_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData StatusTextResponse::_class_data_ = { - StatusTextResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ActuatorOutputStatusResponse::_class_data_ = { + ActuatorOutputStatusResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* StatusTextResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ActuatorOutputStatusResponse::GetClassData() const { return &_class_data_; } -void StatusTextResponse::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.telemetry.StatusTextResponse) +void ActuatorOutputStatusResponse::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.telemetry.ActuatorOutputStatusResponse) 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_status_text()->::mavsdk::rpc::telemetry::StatusText::MergeFrom( - from._internal_status_text()); + _this->_internal_mutable_actuator_output_status()->::mavsdk::rpc::telemetry::ActuatorOutputStatus::MergeFrom( + from._internal_actuator_output_status()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void StatusTextResponse::CopyFrom(const StatusTextResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) +void ActuatorOutputStatusResponse::CopyFrom(const ActuatorOutputStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool StatusTextResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ActuatorOutputStatusResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* StatusTextResponse::AccessCachedSize() const { +::_pbi::CachedSize* ActuatorOutputStatusResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void StatusTextResponse::InternalSwap(StatusTextResponse* PROTOBUF_RESTRICT other) { +void ActuatorOutputStatusResponse::InternalSwap(ActuatorOutputStatusResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.status_text_, other->_impl_.status_text_); + swap(_impl_.actuator_output_status_, other->_impl_.actuator_output_status_); } -::google::protobuf::Metadata StatusTextResponse::GetMetadata() const { +::google::protobuf::Metadata ActuatorOutputStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[37]); } // =================================================================== -class SubscribeActuatorControlTargetRequest::_Internal { +class SubscribeOdometryRequest::_Internal { public: }; -SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena) +SubscribeOdometryRequest::SubscribeOdometryRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeOdometryRequest) } -SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest( +SubscribeOdometryRequest::SubscribeOdometryRequest( ::google::protobuf::Arena* arena, - const SubscribeActuatorControlTargetRequest& from) + const SubscribeOdometryRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeActuatorControlTargetRequest* const _this = this; + SubscribeOdometryRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeOdometryRequest) } @@ -9738,76 +9484,76 @@ SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest( -::google::protobuf::Metadata SubscribeActuatorControlTargetRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeOdometryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[38]); } // =================================================================== -class ActuatorControlTargetResponse::_Internal { +class OdometryResponse::_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(ActuatorControlTargetResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::ActuatorControlTarget& actuator_control_target(const ActuatorControlTargetResponse* msg); - static void set_has_actuator_control_target(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Odometry& odometry(const OdometryResponse* msg); + static void set_has_odometry(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::ActuatorControlTarget& ActuatorControlTargetResponse::_Internal::actuator_control_target(const ActuatorControlTargetResponse* msg) { - return *msg->_impl_.actuator_control_target_; +const ::mavsdk::rpc::telemetry::Odometry& OdometryResponse::_Internal::odometry(const OdometryResponse* msg) { + return *msg->_impl_.odometry_; } -ActuatorControlTargetResponse::ActuatorControlTargetResponse(::google::protobuf::Arena* arena) +OdometryResponse::OdometryResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.OdometryResponse) } -inline PROTOBUF_NDEBUG_INLINE ActuatorControlTargetResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE OdometryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ActuatorControlTargetResponse::ActuatorControlTargetResponse( +OdometryResponse::OdometryResponse( ::google::protobuf::Arena* arena, - const ActuatorControlTargetResponse& from) + const OdometryResponse& from) : ::google::protobuf::Message(arena) { - ActuatorControlTargetResponse* const _this = this; + OdometryResponse* 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_.actuator_control_target_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTarget>(arena, *from._impl_.actuator_control_target_) + _impl_.odometry_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Odometry>(arena, *from._impl_.odometry_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.OdometryResponse) } -inline PROTOBUF_NDEBUG_INLINE ActuatorControlTargetResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE OdometryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ActuatorControlTargetResponse::SharedCtor(::_pb::Arena* arena) { +inline void OdometryResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.actuator_control_target_ = {}; + _impl_.odometry_ = {}; } -ActuatorControlTargetResponse::~ActuatorControlTargetResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) +OdometryResponse::~OdometryResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.OdometryResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ActuatorControlTargetResponse::SharedDtor() { +inline void OdometryResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.actuator_control_target_; + delete _impl_.odometry_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ActuatorControlTargetResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) +PROTOBUF_NOINLINE void OdometryResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.OdometryResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9815,14 +9561,14 @@ PROTOBUF_NOINLINE void ActuatorControlTargetResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.actuator_control_target_ != nullptr); - _impl_.actuator_control_target_->Clear(); + ABSL_DCHECK(_impl_.odometry_ != nullptr); + _impl_.odometry_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ActuatorControlTargetResponse::_InternalParse( +const char* OdometryResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -9830,9 +9576,9 @@ const char* ActuatorControlTargetResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorControlTargetResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> OdometryResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9841,37 +9587,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorControlTargetResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ActuatorControlTargetResponse_default_instance_._instance, + &_OdometryResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + // .mavsdk.rpc.telemetry.Odometry odometry = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_.actuator_control_target_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_.odometry_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; - {PROTOBUF_FIELD_OFFSET(ActuatorControlTargetResponse, _impl_.actuator_control_target_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Odometry odometry = 1; + {PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_.odometry_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ActuatorControlTarget>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Odometry>()}, }}, {{ }}, }; -::uint8_t* ActuatorControlTargetResponse::_InternalSerialize( +::uint8_t* OdometryResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.OdometryResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + // .mavsdk.rpc.telemetry.Odometry odometry = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::actuator_control_target(this), - _Internal::actuator_control_target(this).GetCachedSize(), target, stream); + 1, _Internal::odometry(this), + _Internal::odometry(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -9879,97 +9625,97 @@ ::uint8_t* ActuatorControlTargetResponse::_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.telemetry.ActuatorControlTargetResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.OdometryResponse) return target; } -::size_t ActuatorControlTargetResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) +::size_t OdometryResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.OdometryResponse) ::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.telemetry.ActuatorControlTarget actuator_control_target = 1; + // .mavsdk.rpc.telemetry.Odometry odometry = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.actuator_control_target_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.odometry_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ActuatorControlTargetResponse::_class_data_ = { - ActuatorControlTargetResponse::MergeImpl, +const ::google::protobuf::Message::ClassData OdometryResponse::_class_data_ = { + OdometryResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ActuatorControlTargetResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* OdometryResponse::GetClassData() const { return &_class_data_; } -void ActuatorControlTargetResponse::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.telemetry.ActuatorControlTargetResponse) +void OdometryResponse::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.telemetry.OdometryResponse) 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_actuator_control_target()->::mavsdk::rpc::telemetry::ActuatorControlTarget::MergeFrom( - from._internal_actuator_control_target()); + _this->_internal_mutable_odometry()->::mavsdk::rpc::telemetry::Odometry::MergeFrom( + from._internal_odometry()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ActuatorControlTargetResponse::CopyFrom(const ActuatorControlTargetResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) +void OdometryResponse::CopyFrom(const OdometryResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.OdometryResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ActuatorControlTargetResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool OdometryResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ActuatorControlTargetResponse::AccessCachedSize() const { +::_pbi::CachedSize* OdometryResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ActuatorControlTargetResponse::InternalSwap(ActuatorControlTargetResponse* PROTOBUF_RESTRICT other) { +void OdometryResponse::InternalSwap(OdometryResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.actuator_control_target_, other->_impl_.actuator_control_target_); + swap(_impl_.odometry_, other->_impl_.odometry_); } -::google::protobuf::Metadata ActuatorControlTargetResponse::GetMetadata() const { +::google::protobuf::Metadata OdometryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[39]); } // =================================================================== -class SubscribeActuatorOutputStatusRequest::_Internal { +class SubscribePositionVelocityNedRequest::_Internal { public: }; -SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena) +SubscribePositionVelocityNedRequest::SubscribePositionVelocityNedRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest) } -SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest( +SubscribePositionVelocityNedRequest::SubscribePositionVelocityNedRequest( ::google::protobuf::Arena* arena, - const SubscribeActuatorOutputStatusRequest& from) + const SubscribePositionVelocityNedRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeActuatorOutputStatusRequest* const _this = this; + SubscribePositionVelocityNedRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest) } @@ -9980,76 +9726,76 @@ SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest( -::google::protobuf::Metadata SubscribeActuatorOutputStatusRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribePositionVelocityNedRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[40]); } // =================================================================== -class ActuatorOutputStatusResponse::_Internal { +class PositionVelocityNedResponse::_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(ActuatorOutputStatusResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& actuator_output_status(const ActuatorOutputStatusResponse* msg); - static void set_has_actuator_output_status(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::PositionVelocityNed& position_velocity_ned(const PositionVelocityNedResponse* msg); + static void set_has_position_velocity_ned(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& ActuatorOutputStatusResponse::_Internal::actuator_output_status(const ActuatorOutputStatusResponse* msg) { - return *msg->_impl_.actuator_output_status_; +const ::mavsdk::rpc::telemetry::PositionVelocityNed& PositionVelocityNedResponse::_Internal::position_velocity_ned(const PositionVelocityNedResponse* msg) { + return *msg->_impl_.position_velocity_ned_; } -ActuatorOutputStatusResponse::ActuatorOutputStatusResponse(::google::protobuf::Arena* arena) +PositionVelocityNedResponse::PositionVelocityNedResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) } -inline PROTOBUF_NDEBUG_INLINE ActuatorOutputStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PositionVelocityNedResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ActuatorOutputStatusResponse::ActuatorOutputStatusResponse( +PositionVelocityNedResponse::PositionVelocityNedResponse( ::google::protobuf::Arena* arena, - const ActuatorOutputStatusResponse& from) + const PositionVelocityNedResponse& from) : ::google::protobuf::Message(arena) { - ActuatorOutputStatusResponse* const _this = this; + PositionVelocityNedResponse* 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_.actuator_output_status_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatus>(arena, *from._impl_.actuator_output_status_) + _impl_.position_velocity_ned_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::PositionVelocityNed>(arena, *from._impl_.position_velocity_ned_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) } -inline PROTOBUF_NDEBUG_INLINE ActuatorOutputStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PositionVelocityNedResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ActuatorOutputStatusResponse::SharedCtor(::_pb::Arena* arena) { +inline void PositionVelocityNedResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.actuator_output_status_ = {}; + _impl_.position_velocity_ned_ = {}; } -ActuatorOutputStatusResponse::~ActuatorOutputStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +PositionVelocityNedResponse::~PositionVelocityNedResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ActuatorOutputStatusResponse::SharedDtor() { +inline void PositionVelocityNedResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.actuator_output_status_; + delete _impl_.position_velocity_ned_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ActuatorOutputStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +PROTOBUF_NOINLINE void PositionVelocityNedResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10057,14 +9803,14 @@ PROTOBUF_NOINLINE void ActuatorOutputStatusResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.actuator_output_status_ != nullptr); - _impl_.actuator_output_status_->Clear(); + ABSL_DCHECK(_impl_.position_velocity_ned_ != nullptr); + _impl_.position_velocity_ned_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ActuatorOutputStatusResponse::_InternalParse( +const char* PositionVelocityNedResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10072,9 +9818,9 @@ const char* ActuatorOutputStatusResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorOutputStatusResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PositionVelocityNedResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10083,37 +9829,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ActuatorOutputStatusResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ActuatorOutputStatusResponse_default_instance_._instance, + &_PositionVelocityNedResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_.actuator_output_status_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_.position_velocity_ned_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; - {PROTOBUF_FIELD_OFFSET(ActuatorOutputStatusResponse, _impl_.actuator_output_status_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; + {PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_.position_velocity_ned_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ActuatorOutputStatus>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::PositionVelocityNed>()}, }}, {{ }}, }; -::uint8_t* ActuatorOutputStatusResponse::_InternalSerialize( +::uint8_t* PositionVelocityNedResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::actuator_output_status(this), - _Internal::actuator_output_status(this).GetCachedSize(), target, stream); + 1, _Internal::position_velocity_ned(this), + _Internal::position_velocity_ned(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10121,97 +9867,97 @@ ::uint8_t* ActuatorOutputStatusResponse::_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.telemetry.ActuatorOutputStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.PositionVelocityNedResponse) return target; } -::size_t ActuatorOutputStatusResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +::size_t PositionVelocityNedResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) ::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.telemetry.ActuatorOutputStatus actuator_output_status = 1; + // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.actuator_output_status_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.position_velocity_ned_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ActuatorOutputStatusResponse::_class_data_ = { - ActuatorOutputStatusResponse::MergeImpl, +const ::google::protobuf::Message::ClassData PositionVelocityNedResponse::_class_data_ = { + PositionVelocityNedResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ActuatorOutputStatusResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* PositionVelocityNedResponse::GetClassData() const { return &_class_data_; } -void ActuatorOutputStatusResponse::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.telemetry.ActuatorOutputStatusResponse) +void PositionVelocityNedResponse::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.telemetry.PositionVelocityNedResponse) 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_actuator_output_status()->::mavsdk::rpc::telemetry::ActuatorOutputStatus::MergeFrom( - from._internal_actuator_output_status()); + _this->_internal_mutable_position_velocity_ned()->::mavsdk::rpc::telemetry::PositionVelocityNed::MergeFrom( + from._internal_position_velocity_ned()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ActuatorOutputStatusResponse::CopyFrom(const ActuatorOutputStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +void PositionVelocityNedResponse::CopyFrom(const PositionVelocityNedResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ActuatorOutputStatusResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool PositionVelocityNedResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ActuatorOutputStatusResponse::AccessCachedSize() const { +::_pbi::CachedSize* PositionVelocityNedResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ActuatorOutputStatusResponse::InternalSwap(ActuatorOutputStatusResponse* PROTOBUF_RESTRICT other) { +void PositionVelocityNedResponse::InternalSwap(PositionVelocityNedResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.actuator_output_status_, other->_impl_.actuator_output_status_); + swap(_impl_.position_velocity_ned_, other->_impl_.position_velocity_ned_); } -::google::protobuf::Metadata ActuatorOutputStatusResponse::GetMetadata() const { +::google::protobuf::Metadata PositionVelocityNedResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[41]); } // =================================================================== -class SubscribeOdometryRequest::_Internal { +class SubscribeGroundTruthRequest::_Internal { public: }; -SubscribeOdometryRequest::SubscribeOdometryRequest(::google::protobuf::Arena* arena) +SubscribeGroundTruthRequest::SubscribeGroundTruthRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeOdometryRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeGroundTruthRequest) } -SubscribeOdometryRequest::SubscribeOdometryRequest( +SubscribeGroundTruthRequest::SubscribeGroundTruthRequest( ::google::protobuf::Arena* arena, - const SubscribeOdometryRequest& from) + const SubscribeGroundTruthRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeOdometryRequest* const _this = this; + SubscribeGroundTruthRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeOdometryRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGroundTruthRequest) } @@ -10222,76 +9968,76 @@ SubscribeOdometryRequest::SubscribeOdometryRequest( -::google::protobuf::Metadata SubscribeOdometryRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeGroundTruthRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[42]); } // =================================================================== -class OdometryResponse::_Internal { +class GroundTruthResponse::_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(OdometryResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Odometry& odometry(const OdometryResponse* msg); - static void set_has_odometry(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::GroundTruth& ground_truth(const GroundTruthResponse* msg); + static void set_has_ground_truth(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::Odometry& OdometryResponse::_Internal::odometry(const OdometryResponse* msg) { - return *msg->_impl_.odometry_; +const ::mavsdk::rpc::telemetry::GroundTruth& GroundTruthResponse::_Internal::ground_truth(const GroundTruthResponse* msg) { + return *msg->_impl_.ground_truth_; } -OdometryResponse::OdometryResponse(::google::protobuf::Arena* arena) +GroundTruthResponse::GroundTruthResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.OdometryResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.GroundTruthResponse) } -inline PROTOBUF_NDEBUG_INLINE OdometryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GroundTruthResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -OdometryResponse::OdometryResponse( +GroundTruthResponse::GroundTruthResponse( ::google::protobuf::Arena* arena, - const OdometryResponse& from) + const GroundTruthResponse& from) : ::google::protobuf::Message(arena) { - OdometryResponse* const _this = this; + GroundTruthResponse* 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_.odometry_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Odometry>(arena, *from._impl_.odometry_) + _impl_.ground_truth_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::GroundTruth>(arena, *from._impl_.ground_truth_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.OdometryResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GroundTruthResponse) } -inline PROTOBUF_NDEBUG_INLINE OdometryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GroundTruthResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void OdometryResponse::SharedCtor(::_pb::Arena* arena) { +inline void GroundTruthResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.odometry_ = {}; + _impl_.ground_truth_ = {}; } -OdometryResponse::~OdometryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.OdometryResponse) +GroundTruthResponse::~GroundTruthResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GroundTruthResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void OdometryResponse::SharedDtor() { +inline void GroundTruthResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.odometry_; + delete _impl_.ground_truth_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void OdometryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.OdometryResponse) +PROTOBUF_NOINLINE void GroundTruthResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GroundTruthResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10299,14 +10045,14 @@ PROTOBUF_NOINLINE void OdometryResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.odometry_ != nullptr); - _impl_.odometry_->Clear(); + ABSL_DCHECK(_impl_.ground_truth_ != nullptr); + _impl_.ground_truth_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* OdometryResponse::_InternalParse( +const char* GroundTruthResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10314,9 +10060,9 @@ const char* OdometryResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> OdometryResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GroundTruthResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10325,37 +10071,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> OdometryResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_OdometryResponse_default_instance_._instance, + &_GroundTruthResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Odometry odometry = 1; + // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_.odometry_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_.ground_truth_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Odometry odometry = 1; - {PROTOBUF_FIELD_OFFSET(OdometryResponse, _impl_.odometry_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; + {PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_.ground_truth_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Odometry>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::GroundTruth>()}, }}, {{ }}, }; -::uint8_t* OdometryResponse::_InternalSerialize( +::uint8_t* GroundTruthResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.OdometryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GroundTruthResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Odometry odometry = 1; + // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::odometry(this), - _Internal::odometry(this).GetCachedSize(), target, stream); + 1, _Internal::ground_truth(this), + _Internal::ground_truth(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10363,97 +10109,97 @@ ::uint8_t* OdometryResponse::_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.telemetry.OdometryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GroundTruthResponse) return target; } -::size_t OdometryResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.OdometryResponse) +::size_t GroundTruthResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GroundTruthResponse) ::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.telemetry.Odometry odometry = 1; + // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.odometry_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.ground_truth_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData OdometryResponse::_class_data_ = { - OdometryResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GroundTruthResponse::_class_data_ = { + GroundTruthResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* OdometryResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GroundTruthResponse::GetClassData() const { return &_class_data_; } -void OdometryResponse::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.telemetry.OdometryResponse) +void GroundTruthResponse::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.telemetry.GroundTruthResponse) 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_odometry()->::mavsdk::rpc::telemetry::Odometry::MergeFrom( - from._internal_odometry()); + _this->_internal_mutable_ground_truth()->::mavsdk::rpc::telemetry::GroundTruth::MergeFrom( + from._internal_ground_truth()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void OdometryResponse::CopyFrom(const OdometryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.OdometryResponse) +void GroundTruthResponse::CopyFrom(const GroundTruthResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GroundTruthResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool OdometryResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GroundTruthResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* OdometryResponse::AccessCachedSize() const { +::_pbi::CachedSize* GroundTruthResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void OdometryResponse::InternalSwap(OdometryResponse* PROTOBUF_RESTRICT other) { +void GroundTruthResponse::InternalSwap(GroundTruthResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.odometry_, other->_impl_.odometry_); + swap(_impl_.ground_truth_, other->_impl_.ground_truth_); } -::google::protobuf::Metadata OdometryResponse::GetMetadata() const { +::google::protobuf::Metadata GroundTruthResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[43]); } // =================================================================== -class SubscribePositionVelocityNedRequest::_Internal { +class SubscribeFixedwingMetricsRequest::_Internal { public: }; -SubscribePositionVelocityNedRequest::SubscribePositionVelocityNedRequest(::google::protobuf::Arena* arena) +SubscribeFixedwingMetricsRequest::SubscribeFixedwingMetricsRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest) } -SubscribePositionVelocityNedRequest::SubscribePositionVelocityNedRequest( +SubscribeFixedwingMetricsRequest::SubscribeFixedwingMetricsRequest( ::google::protobuf::Arena* arena, - const SubscribePositionVelocityNedRequest& from) + const SubscribeFixedwingMetricsRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribePositionVelocityNedRequest* const _this = this; + SubscribeFixedwingMetricsRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribePositionVelocityNedRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest) } @@ -10464,76 +10210,76 @@ SubscribePositionVelocityNedRequest::SubscribePositionVelocityNedRequest( -::google::protobuf::Metadata SubscribePositionVelocityNedRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeFixedwingMetricsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[44]); } // =================================================================== -class PositionVelocityNedResponse::_Internal { +class FixedwingMetricsResponse::_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(PositionVelocityNedResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::PositionVelocityNed& position_velocity_ned(const PositionVelocityNedResponse* msg); - static void set_has_position_velocity_ned(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::FixedwingMetrics& fixedwing_metrics(const FixedwingMetricsResponse* msg); + static void set_has_fixedwing_metrics(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::PositionVelocityNed& PositionVelocityNedResponse::_Internal::position_velocity_ned(const PositionVelocityNedResponse* msg) { - return *msg->_impl_.position_velocity_ned_; +const ::mavsdk::rpc::telemetry::FixedwingMetrics& FixedwingMetricsResponse::_Internal::fixedwing_metrics(const FixedwingMetricsResponse* msg) { + return *msg->_impl_.fixedwing_metrics_; } -PositionVelocityNedResponse::PositionVelocityNedResponse(::google::protobuf::Arena* arena) +FixedwingMetricsResponse::FixedwingMetricsResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) } -inline PROTOBUF_NDEBUG_INLINE PositionVelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FixedwingMetricsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PositionVelocityNedResponse::PositionVelocityNedResponse( +FixedwingMetricsResponse::FixedwingMetricsResponse( ::google::protobuf::Arena* arena, - const PositionVelocityNedResponse& from) + const FixedwingMetricsResponse& from) : ::google::protobuf::Message(arena) { - PositionVelocityNedResponse* const _this = this; + FixedwingMetricsResponse* 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_.position_velocity_ned_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::PositionVelocityNed>(arena, *from._impl_.position_velocity_ned_) + _impl_.fixedwing_metrics_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::FixedwingMetrics>(arena, *from._impl_.fixedwing_metrics_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) } -inline PROTOBUF_NDEBUG_INLINE PositionVelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE FixedwingMetricsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PositionVelocityNedResponse::SharedCtor(::_pb::Arena* arena) { +inline void FixedwingMetricsResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.position_velocity_ned_ = {}; + _impl_.fixedwing_metrics_ = {}; } -PositionVelocityNedResponse::~PositionVelocityNedResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.PositionVelocityNedResponse) +FixedwingMetricsResponse::~FixedwingMetricsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void PositionVelocityNedResponse::SharedDtor() { +inline void FixedwingMetricsResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.position_velocity_ned_; + delete _impl_.fixedwing_metrics_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void PositionVelocityNedResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) +PROTOBUF_NOINLINE void FixedwingMetricsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10541,14 +10287,14 @@ PROTOBUF_NOINLINE void PositionVelocityNedResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.position_velocity_ned_ != nullptr); - _impl_.position_velocity_ned_->Clear(); + ABSL_DCHECK(_impl_.fixedwing_metrics_ != nullptr); + _impl_.fixedwing_metrics_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* PositionVelocityNedResponse::_InternalParse( +const char* FixedwingMetricsResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10556,9 +10302,9 @@ const char* PositionVelocityNedResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PositionVelocityNedResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FixedwingMetricsResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10567,37 +10313,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PositionVelocityNedResponse::_table_ = 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_PositionVelocityNedResponse_default_instance_._instance, + &_FixedwingMetricsResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; + // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_.position_velocity_ned_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_.fixedwing_metrics_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; - {PROTOBUF_FIELD_OFFSET(PositionVelocityNedResponse, _impl_.position_velocity_ned_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; + {PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_.fixedwing_metrics_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::PositionVelocityNed>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::FixedwingMetrics>()}, }}, {{ }}, }; -::uint8_t* PositionVelocityNedResponse::_InternalSerialize( +::uint8_t* FixedwingMetricsResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.PositionVelocityNed position_velocity_ned = 1; + // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::position_velocity_ned(this), - _Internal::position_velocity_ned(this).GetCachedSize(), target, stream); + 1, _Internal::fixedwing_metrics(this), + _Internal::fixedwing_metrics(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10605,97 +10351,97 @@ ::uint8_t* PositionVelocityNedResponse::_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.telemetry.PositionVelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.FixedwingMetricsResponse) return target; } -::size_t PositionVelocityNedResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) +::size_t FixedwingMetricsResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) ::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.telemetry.PositionVelocityNed position_velocity_ned = 1; + // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.position_velocity_ned_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.fixedwing_metrics_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData PositionVelocityNedResponse::_class_data_ = { - PositionVelocityNedResponse::MergeImpl, +const ::google::protobuf::Message::ClassData FixedwingMetricsResponse::_class_data_ = { + FixedwingMetricsResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* PositionVelocityNedResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* FixedwingMetricsResponse::GetClassData() const { return &_class_data_; } -void PositionVelocityNedResponse::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.telemetry.PositionVelocityNedResponse) +void FixedwingMetricsResponse::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.telemetry.FixedwingMetricsResponse) 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_position_velocity_ned()->::mavsdk::rpc::telemetry::PositionVelocityNed::MergeFrom( - from._internal_position_velocity_ned()); + _this->_internal_mutable_fixedwing_metrics()->::mavsdk::rpc::telemetry::FixedwingMetrics::MergeFrom( + from._internal_fixedwing_metrics()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PositionVelocityNedResponse::CopyFrom(const PositionVelocityNedResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.PositionVelocityNedResponse) +void FixedwingMetricsResponse::CopyFrom(const FixedwingMetricsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool PositionVelocityNedResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool FixedwingMetricsResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* PositionVelocityNedResponse::AccessCachedSize() const { +::_pbi::CachedSize* FixedwingMetricsResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void PositionVelocityNedResponse::InternalSwap(PositionVelocityNedResponse* PROTOBUF_RESTRICT other) { +void FixedwingMetricsResponse::InternalSwap(FixedwingMetricsResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.position_velocity_ned_, other->_impl_.position_velocity_ned_); + swap(_impl_.fixedwing_metrics_, other->_impl_.fixedwing_metrics_); } -::google::protobuf::Metadata PositionVelocityNedResponse::GetMetadata() const { +::google::protobuf::Metadata FixedwingMetricsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[45]); } // =================================================================== -class SubscribeGroundTruthRequest::_Internal { +class SubscribeImuRequest::_Internal { public: }; -SubscribeGroundTruthRequest::SubscribeGroundTruthRequest(::google::protobuf::Arena* arena) +SubscribeImuRequest::SubscribeImuRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeGroundTruthRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeImuRequest) } -SubscribeGroundTruthRequest::SubscribeGroundTruthRequest( +SubscribeImuRequest::SubscribeImuRequest( ::google::protobuf::Arena* arena, - const SubscribeGroundTruthRequest& from) + const SubscribeImuRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeGroundTruthRequest* const _this = this; + SubscribeImuRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGroundTruthRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeImuRequest) } @@ -10706,76 +10452,76 @@ SubscribeGroundTruthRequest::SubscribeGroundTruthRequest( -::google::protobuf::Metadata SubscribeGroundTruthRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[46]); } // =================================================================== -class GroundTruthResponse::_Internal { +class ImuResponse::_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(GroundTruthResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::GroundTruth& ground_truth(const GroundTruthResponse* msg); - static void set_has_ground_truth(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Imu& imu(const ImuResponse* msg); + static void set_has_imu(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::GroundTruth& GroundTruthResponse::_Internal::ground_truth(const GroundTruthResponse* msg) { - return *msg->_impl_.ground_truth_; +const ::mavsdk::rpc::telemetry::Imu& ImuResponse::_Internal::imu(const ImuResponse* msg) { + return *msg->_impl_.imu_; } -GroundTruthResponse::GroundTruthResponse(::google::protobuf::Arena* arena) +ImuResponse::ImuResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.GroundTruthResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ImuResponse) } -inline PROTOBUF_NDEBUG_INLINE GroundTruthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -GroundTruthResponse::GroundTruthResponse( +ImuResponse::ImuResponse( ::google::protobuf::Arena* arena, - const GroundTruthResponse& from) + const ImuResponse& from) : ::google::protobuf::Message(arena) { - GroundTruthResponse* const _this = this; + ImuResponse* 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_.ground_truth_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::GroundTruth>(arena, *from._impl_.ground_truth_) + _impl_.imu_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Imu>(arena, *from._impl_.imu_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GroundTruthResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ImuResponse) } -inline PROTOBUF_NDEBUG_INLINE GroundTruthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void GroundTruthResponse::SharedCtor(::_pb::Arena* arena) { +inline void ImuResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.ground_truth_ = {}; + _impl_.imu_ = {}; } -GroundTruthResponse::~GroundTruthResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GroundTruthResponse) +ImuResponse::~ImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ImuResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void GroundTruthResponse::SharedDtor() { +inline void ImuResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.ground_truth_; + delete _impl_.imu_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void GroundTruthResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GroundTruthResponse) +PROTOBUF_NOINLINE void ImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ImuResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10783,14 +10529,14 @@ PROTOBUF_NOINLINE void GroundTruthResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.ground_truth_ != nullptr); - _impl_.ground_truth_->Clear(); + ABSL_DCHECK(_impl_.imu_ != nullptr); + _impl_.imu_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* GroundTruthResponse::_InternalParse( +const char* ImuResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -10798,9 +10544,9 @@ const char* GroundTruthResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GroundTruthResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10809,37 +10555,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GroundTruthResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_GroundTruthResponse_default_instance_._instance, + &_ImuResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_.ground_truth_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_.imu_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; - {PROTOBUF_FIELD_OFFSET(GroundTruthResponse, _impl_.ground_truth_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Imu imu = 1; + {PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::GroundTruth>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Imu>()}, }}, {{ }}, }; -::uint8_t* GroundTruthResponse::_InternalSerialize( +::uint8_t* ImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GroundTruthResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::ground_truth(this), - _Internal::ground_truth(this).GetCachedSize(), target, stream); + 1, _Internal::imu(this), + _Internal::imu(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -10847,97 +10593,97 @@ ::uint8_t* GroundTruthResponse::_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.telemetry.GroundTruthResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ImuResponse) return target; } -::size_t GroundTruthResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GroundTruthResponse) +::size_t ImuResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ImuResponse) ::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.telemetry.GroundTruth ground_truth = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.ground_truth_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.imu_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData GroundTruthResponse::_class_data_ = { - GroundTruthResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ImuResponse::_class_data_ = { + ImuResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* GroundTruthResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ImuResponse::GetClassData() const { return &_class_data_; } -void GroundTruthResponse::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.telemetry.GroundTruthResponse) +void ImuResponse::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.telemetry.ImuResponse) 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_ground_truth()->::mavsdk::rpc::telemetry::GroundTruth::MergeFrom( - from._internal_ground_truth()); + _this->_internal_mutable_imu()->::mavsdk::rpc::telemetry::Imu::MergeFrom( + from._internal_imu()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void GroundTruthResponse::CopyFrom(const GroundTruthResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GroundTruthResponse) +void ImuResponse::CopyFrom(const ImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool GroundTruthResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ImuResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* GroundTruthResponse::AccessCachedSize() const { +::_pbi::CachedSize* ImuResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void GroundTruthResponse::InternalSwap(GroundTruthResponse* PROTOBUF_RESTRICT other) { +void ImuResponse::InternalSwap(ImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.ground_truth_, other->_impl_.ground_truth_); + swap(_impl_.imu_, other->_impl_.imu_); } -::google::protobuf::Metadata GroundTruthResponse::GetMetadata() const { +::google::protobuf::Metadata ImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[47]); } // =================================================================== -class SubscribeFixedwingMetricsRequest::_Internal { +class SubscribeScaledImuRequest::_Internal { public: }; -SubscribeFixedwingMetricsRequest::SubscribeFixedwingMetricsRequest(::google::protobuf::Arena* arena) +SubscribeScaledImuRequest::SubscribeScaledImuRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeScaledImuRequest) } -SubscribeFixedwingMetricsRequest::SubscribeFixedwingMetricsRequest( +SubscribeScaledImuRequest::SubscribeScaledImuRequest( ::google::protobuf::Arena* arena, - const SubscribeFixedwingMetricsRequest& from) + const SubscribeScaledImuRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeFixedwingMetricsRequest* const _this = this; + SubscribeScaledImuRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFixedwingMetricsRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeScaledImuRequest) } @@ -10948,76 +10694,76 @@ SubscribeFixedwingMetricsRequest::SubscribeFixedwingMetricsRequest( -::google::protobuf::Metadata SubscribeFixedwingMetricsRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeScaledImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[48]); } // =================================================================== -class FixedwingMetricsResponse::_Internal { +class ScaledImuResponse::_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(FixedwingMetricsResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::FixedwingMetrics& fixedwing_metrics(const FixedwingMetricsResponse* msg); - static void set_has_fixedwing_metrics(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Imu& imu(const ScaledImuResponse* msg); + static void set_has_imu(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::FixedwingMetrics& FixedwingMetricsResponse::_Internal::fixedwing_metrics(const FixedwingMetricsResponse* msg) { - return *msg->_impl_.fixedwing_metrics_; +const ::mavsdk::rpc::telemetry::Imu& ScaledImuResponse::_Internal::imu(const ScaledImuResponse* msg) { + return *msg->_impl_.imu_; } -FixedwingMetricsResponse::FixedwingMetricsResponse(::google::protobuf::Arena* arena) +ScaledImuResponse::ScaledImuResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ScaledImuResponse) } -inline PROTOBUF_NDEBUG_INLINE FixedwingMetricsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ScaledImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -FixedwingMetricsResponse::FixedwingMetricsResponse( +ScaledImuResponse::ScaledImuResponse( ::google::protobuf::Arena* arena, - const FixedwingMetricsResponse& from) + const ScaledImuResponse& from) : ::google::protobuf::Message(arena) { - FixedwingMetricsResponse* const _this = this; + ScaledImuResponse* 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_.fixedwing_metrics_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::FixedwingMetrics>(arena, *from._impl_.fixedwing_metrics_) + _impl_.imu_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Imu>(arena, *from._impl_.imu_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ScaledImuResponse) } -inline PROTOBUF_NDEBUG_INLINE FixedwingMetricsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ScaledImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void FixedwingMetricsResponse::SharedCtor(::_pb::Arena* arena) { +inline void ScaledImuResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.fixedwing_metrics_ = {}; + _impl_.imu_ = {}; } -FixedwingMetricsResponse::~FixedwingMetricsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FixedwingMetricsResponse) +ScaledImuResponse::~ScaledImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ScaledImuResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void FixedwingMetricsResponse::SharedDtor() { +inline void ScaledImuResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.fixedwing_metrics_; + delete _impl_.imu_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void FixedwingMetricsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) +PROTOBUF_NOINLINE void ScaledImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ScaledImuResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -11025,14 +10771,14 @@ PROTOBUF_NOINLINE void FixedwingMetricsResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.fixedwing_metrics_ != nullptr); - _impl_.fixedwing_metrics_->Clear(); + ABSL_DCHECK(_impl_.imu_ != nullptr); + _impl_.imu_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* FixedwingMetricsResponse::_InternalParse( +const char* ScaledImuResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11040,9 +10786,9 @@ const char* FixedwingMetricsResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FixedwingMetricsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ScaledImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -11051,37 +10797,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> FixedwingMetricsResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_FixedwingMetricsResponse_default_instance_._instance, + &_ScaledImuResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_.fixedwing_metrics_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_.imu_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; - {PROTOBUF_FIELD_OFFSET(FixedwingMetricsResponse, _impl_.fixedwing_metrics_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Imu imu = 1; + {PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::FixedwingMetrics>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Imu>()}, }}, {{ }}, }; -::uint8_t* FixedwingMetricsResponse::_InternalSerialize( +::uint8_t* ScaledImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ScaledImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::fixedwing_metrics(this), - _Internal::fixedwing_metrics(this).GetCachedSize(), target, stream); + 1, _Internal::imu(this), + _Internal::imu(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11089,97 +10835,97 @@ ::uint8_t* FixedwingMetricsResponse::_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.telemetry.FixedwingMetricsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ScaledImuResponse) return target; } -::size_t FixedwingMetricsResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) +::size_t ScaledImuResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ScaledImuResponse) ::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.telemetry.FixedwingMetrics fixedwing_metrics = 1; + // .mavsdk.rpc.telemetry.Imu imu = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.fixedwing_metrics_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.imu_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData FixedwingMetricsResponse::_class_data_ = { - FixedwingMetricsResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ScaledImuResponse::_class_data_ = { + ScaledImuResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* FixedwingMetricsResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ScaledImuResponse::GetClassData() const { return &_class_data_; } -void FixedwingMetricsResponse::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.telemetry.FixedwingMetricsResponse) +void ScaledImuResponse::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.telemetry.ScaledImuResponse) 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_fixedwing_metrics()->::mavsdk::rpc::telemetry::FixedwingMetrics::MergeFrom( - from._internal_fixedwing_metrics()); + _this->_internal_mutable_imu()->::mavsdk::rpc::telemetry::Imu::MergeFrom( + from._internal_imu()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void FixedwingMetricsResponse::CopyFrom(const FixedwingMetricsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FixedwingMetricsResponse) +void ScaledImuResponse::CopyFrom(const ScaledImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ScaledImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool FixedwingMetricsResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ScaledImuResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* FixedwingMetricsResponse::AccessCachedSize() const { +::_pbi::CachedSize* ScaledImuResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void FixedwingMetricsResponse::InternalSwap(FixedwingMetricsResponse* PROTOBUF_RESTRICT other) { +void ScaledImuResponse::InternalSwap(ScaledImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.fixedwing_metrics_, other->_impl_.fixedwing_metrics_); + swap(_impl_.imu_, other->_impl_.imu_); } -::google::protobuf::Metadata FixedwingMetricsResponse::GetMetadata() const { +::google::protobuf::Metadata ScaledImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[49]); } // =================================================================== -class SubscribeImuRequest::_Internal { +class SubscribeRawImuRequest::_Internal { public: }; -SubscribeImuRequest::SubscribeImuRequest(::google::protobuf::Arena* arena) +SubscribeRawImuRequest::SubscribeRawImuRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeImuRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRawImuRequest) } -SubscribeImuRequest::SubscribeImuRequest( +SubscribeRawImuRequest::SubscribeRawImuRequest( ::google::protobuf::Arena* arena, - const SubscribeImuRequest& from) + const SubscribeRawImuRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeImuRequest* const _this = this; + SubscribeRawImuRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeImuRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRawImuRequest) } @@ -11190,43 +10936,43 @@ SubscribeImuRequest::SubscribeImuRequest( -::google::protobuf::Metadata SubscribeImuRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeRawImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[50]); } // =================================================================== -class ImuResponse::_Internal { +class RawImuResponse::_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(ImuResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Imu& imu(const ImuResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Imu& imu(const RawImuResponse* msg); static void set_has_imu(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::Imu& ImuResponse::_Internal::imu(const ImuResponse* msg) { +const ::mavsdk::rpc::telemetry::Imu& RawImuResponse::_Internal::imu(const RawImuResponse* msg) { return *msg->_impl_.imu_; } -ImuResponse::ImuResponse(::google::protobuf::Arena* arena) +RawImuResponse::RawImuResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RawImuResponse) } -inline PROTOBUF_NDEBUG_INLINE ImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RawImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ImuResponse::ImuResponse( +RawImuResponse::RawImuResponse( ::google::protobuf::Arena* arena, - const ImuResponse& from) + const RawImuResponse& from) : ::google::protobuf::Message(arena) { - ImuResponse* const _this = this; + RawImuResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -11236,30 +10982,30 @@ ImuResponse::ImuResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Imu>(arena, *from._impl_.imu_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ImuResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RawImuResponse) } -inline PROTOBUF_NDEBUG_INLINE ImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE RawImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void RawImuResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.imu_ = {}; } -ImuResponse::~ImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ImuResponse) +RawImuResponse::~RawImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RawImuResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ImuResponse::SharedDtor() { +inline void RawImuResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.imu_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ImuResponse) +PROTOBUF_NOINLINE void RawImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RawImuResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -11274,7 +11020,7 @@ PROTOBUF_NOINLINE void ImuResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ImuResponse::_InternalParse( +const char* RawImuResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11282,9 +11028,9 @@ const char* ImuResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RawImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -11293,17 +11039,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ImuResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ImuResponse_default_instance_._instance, + &_RawImuResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.Imu imu = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_.imu_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_.imu_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.Imu imu = 1; - {PROTOBUF_FIELD_OFFSET(ImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Imu>()}, @@ -11311,10 +11057,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ImuResponse::_table_ = { }}, }; -::uint8_t* ImuResponse::_InternalSerialize( +::uint8_t* RawImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RawImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -11331,12 +11077,12 @@ ::uint8_t* ImuResponse::_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.telemetry.ImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RawImuResponse) return target; } -::size_t ImuResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ImuResponse) +::size_t RawImuResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RawImuResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -11353,18 +11099,18 @@ ::size_t ImuResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ImuResponse::_class_data_ = { - ImuResponse::MergeImpl, +const ::google::protobuf::Message::ClassData RawImuResponse::_class_data_ = { + RawImuResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ImuResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* RawImuResponse::GetClassData() const { return &_class_data_; } -void ImuResponse::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.telemetry.ImuResponse) +void RawImuResponse::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.telemetry.RawImuResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -11376,52 +11122,52 @@ void ImuResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google: _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ImuResponse::CopyFrom(const ImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ImuResponse) +void RawImuResponse::CopyFrom(const RawImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RawImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ImuResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool RawImuResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ImuResponse::AccessCachedSize() const { +::_pbi::CachedSize* RawImuResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ImuResponse::InternalSwap(ImuResponse* PROTOBUF_RESTRICT other) { +void RawImuResponse::InternalSwap(RawImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.imu_, other->_impl_.imu_); } -::google::protobuf::Metadata ImuResponse::GetMetadata() const { +::google::protobuf::Metadata RawImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[51]); } // =================================================================== -class SubscribeScaledImuRequest::_Internal { +class SubscribeHealthAllOkRequest::_Internal { public: }; -SubscribeScaledImuRequest::SubscribeScaledImuRequest(::google::protobuf::Arena* arena) +SubscribeHealthAllOkRequest::SubscribeHealthAllOkRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeScaledImuRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest) } -SubscribeScaledImuRequest::SubscribeScaledImuRequest( +SubscribeHealthAllOkRequest::SubscribeHealthAllOkRequest( ::google::protobuf::Arena* arena, - const SubscribeScaledImuRequest& from) + const SubscribeHealthAllOkRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeScaledImuRequest* const _this = this; + SubscribeHealthAllOkRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeScaledImuRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest) } @@ -11432,91 +11178,58 @@ SubscribeScaledImuRequest::SubscribeScaledImuRequest( -::google::protobuf::Metadata SubscribeScaledImuRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeHealthAllOkRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[52]); } // =================================================================== -class ScaledImuResponse::_Internal { +class HealthAllOkResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Imu& imu(const ScaledImuResponse* msg); - static void set_has_imu(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::telemetry::Imu& ScaledImuResponse::_Internal::imu(const ScaledImuResponse* msg) { - return *msg->_impl_.imu_; -} -ScaledImuResponse::ScaledImuResponse(::google::protobuf::Arena* arena) +HealthAllOkResponse::HealthAllOkResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ScaledImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HealthAllOkResponse) } -inline PROTOBUF_NDEBUG_INLINE ScaledImuResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -ScaledImuResponse::ScaledImuResponse( - ::google::protobuf::Arena* arena, - const ScaledImuResponse& from) - : ::google::protobuf::Message(arena) { - ScaledImuResponse* 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_.imu_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Imu>(arena, *from._impl_.imu_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ScaledImuResponse) +HealthAllOkResponse::HealthAllOkResponse( + ::google::protobuf::Arena* arena, const HealthAllOkResponse& from) + : HealthAllOkResponse(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE ScaledImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE HealthAllOkResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ScaledImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void HealthAllOkResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.imu_ = {}; + _impl_.is_health_all_ok_ = {}; } -ScaledImuResponse::~ScaledImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ScaledImuResponse) +HealthAllOkResponse::~HealthAllOkResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthAllOkResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ScaledImuResponse::SharedDtor() { +inline void HealthAllOkResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.imu_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ScaledImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ScaledImuResponse) +PROTOBUF_NOINLINE void HealthAllOkResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthAllOkResponse) 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_.imu_ != nullptr); - _impl_.imu_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.is_health_all_ok_ = false; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ScaledImuResponse::_InternalParse( +const char* HealthAllOkResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11524,48 +11237,47 @@ const char* ScaledImuResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ScaledImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> HealthAllOkResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_ScaledImuResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_HealthAllOkResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Imu imu = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_.imu_)}}, + // bool is_health_all_ok = 1; + {::_pbi::TcParser::SingularVarintNoZag1(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAllOkResponse, _impl_.is_health_all_ok_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Imu imu = 1; - {PROTOBUF_FIELD_OFFSET(ScaledImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Imu>()}, - }}, {{ + // bool is_health_all_ok = 1; + {PROTOBUF_FIELD_OFFSET(HealthAllOkResponse, _impl_.is_health_all_ok_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* ScaledImuResponse::_InternalSerialize( +::uint8_t* HealthAllOkResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ScaledImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthAllOkResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Imu imu = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::imu(this), - _Internal::imu(this).GetCachedSize(), target, stream); + // bool is_health_all_ok = 1; + if (this->_internal_is_health_all_ok() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 1, this->_internal_is_health_all_ok(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11573,97 +11285,93 @@ ::uint8_t* ScaledImuResponse::_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.telemetry.ScaledImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.HealthAllOkResponse) return target; } -::size_t ScaledImuResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ScaledImuResponse) +::size_t HealthAllOkResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthAllOkResponse) ::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.telemetry.Imu imu = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.imu_); + // bool is_health_all_ok = 1; + if (this->_internal_is_health_all_ok() != 0) { + total_size += 2; } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ScaledImuResponse::_class_data_ = { - ScaledImuResponse::MergeImpl, +const ::google::protobuf::Message::ClassData HealthAllOkResponse::_class_data_ = { + HealthAllOkResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ScaledImuResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* HealthAllOkResponse::GetClassData() const { return &_class_data_; } -void ScaledImuResponse::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.telemetry.ScaledImuResponse) +void HealthAllOkResponse::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.telemetry.HealthAllOkResponse) 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_imu()->::mavsdk::rpc::telemetry::Imu::MergeFrom( - from._internal_imu()); + if (from._internal_is_health_all_ok() != 0) { + _this->_internal_set_is_health_all_ok(from._internal_is_health_all_ok()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ScaledImuResponse::CopyFrom(const ScaledImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ScaledImuResponse) +void HealthAllOkResponse::CopyFrom(const HealthAllOkResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthAllOkResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ScaledImuResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool HealthAllOkResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ScaledImuResponse::AccessCachedSize() const { +::_pbi::CachedSize* HealthAllOkResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ScaledImuResponse::InternalSwap(ScaledImuResponse* PROTOBUF_RESTRICT other) { +void HealthAllOkResponse::InternalSwap(HealthAllOkResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.imu_, other->_impl_.imu_); + swap(_impl_.is_health_all_ok_, other->_impl_.is_health_all_ok_); } -::google::protobuf::Metadata ScaledImuResponse::GetMetadata() const { +::google::protobuf::Metadata HealthAllOkResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[53]); } // =================================================================== -class SubscribeRawImuRequest::_Internal { +class SubscribeUnixEpochTimeRequest::_Internal { public: }; -SubscribeRawImuRequest::SubscribeRawImuRequest(::google::protobuf::Arena* arena) +SubscribeUnixEpochTimeRequest::SubscribeUnixEpochTimeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeRawImuRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest) } -SubscribeRawImuRequest::SubscribeRawImuRequest( +SubscribeUnixEpochTimeRequest::SubscribeUnixEpochTimeRequest( ::google::protobuf::Arena* arena, - const SubscribeRawImuRequest& from) + const SubscribeUnixEpochTimeRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeRawImuRequest* const _this = this; + SubscribeUnixEpochTimeRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRawImuRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest) } @@ -11674,91 +11382,58 @@ SubscribeRawImuRequest::SubscribeRawImuRequest( -::google::protobuf::Metadata SubscribeRawImuRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeUnixEpochTimeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[54]); } // =================================================================== -class RawImuResponse::_Internal { +class UnixEpochTimeResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Imu& imu(const RawImuResponse* msg); - static void set_has_imu(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::telemetry::Imu& RawImuResponse::_Internal::imu(const RawImuResponse* msg) { - return *msg->_impl_.imu_; -} -RawImuResponse::RawImuResponse(::google::protobuf::Arena* arena) +UnixEpochTimeResponse::UnixEpochTimeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.RawImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.UnixEpochTimeResponse) } -inline PROTOBUF_NDEBUG_INLINE RawImuResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -RawImuResponse::RawImuResponse( - ::google::protobuf::Arena* arena, - const RawImuResponse& from) - : ::google::protobuf::Message(arena) { - RawImuResponse* 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_.imu_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Imu>(arena, *from._impl_.imu_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RawImuResponse) +UnixEpochTimeResponse::UnixEpochTimeResponse( + ::google::protobuf::Arena* arena, const UnixEpochTimeResponse& from) + : UnixEpochTimeResponse(arena) { + MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE RawImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE UnixEpochTimeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void RawImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void UnixEpochTimeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.imu_ = {}; + _impl_.time_us_ = {}; } -RawImuResponse::~RawImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RawImuResponse) +UnixEpochTimeResponse::~UnixEpochTimeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.UnixEpochTimeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void RawImuResponse::SharedDtor() { +inline void UnixEpochTimeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.imu_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void RawImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RawImuResponse) +PROTOBUF_NOINLINE void UnixEpochTimeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) 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_.imu_ != nullptr); - _impl_.imu_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.time_us_ = ::uint64_t{0u}; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* RawImuResponse::_InternalParse( +const char* UnixEpochTimeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11766,48 +11441,47 @@ const char* RawImuResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> RawImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> UnixEpochTimeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967294, // skipmap offsetof(decltype(_table_), field_entries), 1, // num_field_entries - 1, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_RawImuResponse_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_UnixEpochTimeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.Imu imu = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_.imu_)}}, + // uint64 time_us = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint64_t, offsetof(UnixEpochTimeResponse, _impl_.time_us_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(UnixEpochTimeResponse, _impl_.time_us_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.Imu imu = 1; - {PROTOBUF_FIELD_OFFSET(RawImuResponse, _impl_.imu_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Imu>()}, - }}, {{ + // uint64 time_us = 1; + {PROTOBUF_FIELD_OFFSET(UnixEpochTimeResponse, _impl_.time_us_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt64)}, + }}, + // no aux_entries + {{ }}, }; -::uint8_t* RawImuResponse::_InternalSerialize( +::uint8_t* UnixEpochTimeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RawImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Imu imu = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::imu(this), - _Internal::imu(this).GetCachedSize(), target, stream); + // uint64 time_us = 1; + if (this->_internal_time_us() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt64ToArray( + 1, this->_internal_time_us(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -11815,97 +11489,94 @@ ::uint8_t* RawImuResponse::_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.telemetry.RawImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.UnixEpochTimeResponse) return target; } -::size_t RawImuResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RawImuResponse) +::size_t UnixEpochTimeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) ::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.telemetry.Imu imu = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.imu_); + // uint64 time_us = 1; + if (this->_internal_time_us() != 0) { + total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( + this->_internal_time_us()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData RawImuResponse::_class_data_ = { - RawImuResponse::MergeImpl, +const ::google::protobuf::Message::ClassData UnixEpochTimeResponse::_class_data_ = { + UnixEpochTimeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* RawImuResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* UnixEpochTimeResponse::GetClassData() const { return &_class_data_; } -void RawImuResponse::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.telemetry.RawImuResponse) +void UnixEpochTimeResponse::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.telemetry.UnixEpochTimeResponse) 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_imu()->::mavsdk::rpc::telemetry::Imu::MergeFrom( - from._internal_imu()); + if (from._internal_time_us() != 0) { + _this->_internal_set_time_us(from._internal_time_us()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void RawImuResponse::CopyFrom(const RawImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RawImuResponse) +void UnixEpochTimeResponse::CopyFrom(const UnixEpochTimeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool RawImuResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool UnixEpochTimeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* RawImuResponse::AccessCachedSize() const { +::_pbi::CachedSize* UnixEpochTimeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void RawImuResponse::InternalSwap(RawImuResponse* PROTOBUF_RESTRICT other) { +void UnixEpochTimeResponse::InternalSwap(UnixEpochTimeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.imu_, other->_impl_.imu_); + swap(_impl_.time_us_, other->_impl_.time_us_); } -::google::protobuf::Metadata RawImuResponse::GetMetadata() const { +::google::protobuf::Metadata UnixEpochTimeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[55]); } // =================================================================== -class SubscribeHealthAllOkRequest::_Internal { +class SubscribeDistanceSensorRequest::_Internal { public: }; -SubscribeHealthAllOkRequest::SubscribeHealthAllOkRequest(::google::protobuf::Arena* arena) +SubscribeDistanceSensorRequest::SubscribeDistanceSensorRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest) } -SubscribeHealthAllOkRequest::SubscribeHealthAllOkRequest( +SubscribeDistanceSensorRequest::SubscribeDistanceSensorRequest( ::google::protobuf::Arena* arena, - const SubscribeHealthAllOkRequest& from) + const SubscribeDistanceSensorRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeHealthAllOkRequest* const _this = this; + SubscribeDistanceSensorRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthAllOkRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest) } @@ -11916,58 +11587,91 @@ SubscribeHealthAllOkRequest::SubscribeHealthAllOkRequest( -::google::protobuf::Metadata SubscribeHealthAllOkRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeDistanceSensorRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[56]); } // =================================================================== -class HealthAllOkResponse::_Internal { +class DistanceSensorResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::DistanceSensor& distance_sensor(const DistanceSensorResponse* msg); + static void set_has_distance_sensor(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -HealthAllOkResponse::HealthAllOkResponse(::google::protobuf::Arena* arena) +const ::mavsdk::rpc::telemetry::DistanceSensor& DistanceSensorResponse::_Internal::distance_sensor(const DistanceSensorResponse* msg) { + return *msg->_impl_.distance_sensor_; +} +DistanceSensorResponse::DistanceSensorResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HealthAllOkResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.DistanceSensorResponse) } -HealthAllOkResponse::HealthAllOkResponse( - ::google::protobuf::Arena* arena, const HealthAllOkResponse& from) - : HealthAllOkResponse(arena) { - MergeFrom(from); +inline PROTOBUF_NDEBUG_INLINE DistanceSensorResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +DistanceSensorResponse::DistanceSensorResponse( + ::google::protobuf::Arena* arena, + const DistanceSensorResponse& from) + : ::google::protobuf::Message(arena) { + DistanceSensorResponse* 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_.distance_sensor_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::DistanceSensor>(arena, *from._impl_.distance_sensor_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.DistanceSensorResponse) } -inline PROTOBUF_NDEBUG_INLINE HealthAllOkResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE DistanceSensorResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void HealthAllOkResponse::SharedCtor(::_pb::Arena* arena) { +inline void DistanceSensorResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.is_health_all_ok_ = {}; + _impl_.distance_sensor_ = {}; } -HealthAllOkResponse::~HealthAllOkResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthAllOkResponse) +DistanceSensorResponse::~DistanceSensorResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.DistanceSensorResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void HealthAllOkResponse::SharedDtor() { +inline void DistanceSensorResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.distance_sensor_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void HealthAllOkResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthAllOkResponse) +PROTOBUF_NOINLINE void DistanceSensorResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.DistanceSensorResponse) 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_.is_health_all_ok_ = false; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.distance_sensor_ != nullptr); + _impl_.distance_sensor_->Clear(); + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* HealthAllOkResponse::_InternalParse( +const char* DistanceSensorResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -11975,47 +11679,48 @@ const char* HealthAllOkResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> HealthAllOkResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> DistanceSensorResponse::_table_ = { { - 0, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _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 - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_HealthAllOkResponse_default_instance_._instance, + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_DistanceSensorResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // bool is_health_all_ok = 1; - {::_pbi::TcParser::SingularVarintNoZag1(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(HealthAllOkResponse, _impl_.is_health_all_ok_)}}, + // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _impl_.distance_sensor_)}}, }}, {{ 65535, 65535 }}, {{ - // bool is_health_all_ok = 1; - {PROTOBUF_FIELD_OFFSET(HealthAllOkResponse, _impl_.is_health_all_ok_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kBool)}, - }}, - // no aux_entries - {{ + // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; + {PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _impl_.distance_sensor_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::DistanceSensor>()}, + }}, {{ }}, }; -::uint8_t* HealthAllOkResponse::_InternalSerialize( +::uint8_t* DistanceSensorResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthAllOkResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.DistanceSensorResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // bool is_health_all_ok = 1; - if (this->_internal_is_health_all_ok() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteBoolToArray( - 1, this->_internal_is_health_all_ok(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::distance_sensor(this), + _Internal::distance_sensor(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -12023,93 +11728,97 @@ ::uint8_t* HealthAllOkResponse::_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.telemetry.HealthAllOkResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.DistanceSensorResponse) return target; } -::size_t HealthAllOkResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthAllOkResponse) +::size_t DistanceSensorResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.DistanceSensorResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // bool is_health_all_ok = 1; - if (this->_internal_is_health_all_ok() != 0) { - total_size += 2; + // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.distance_sensor_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData HealthAllOkResponse::_class_data_ = { - HealthAllOkResponse::MergeImpl, +const ::google::protobuf::Message::ClassData DistanceSensorResponse::_class_data_ = { + DistanceSensorResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* HealthAllOkResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* DistanceSensorResponse::GetClassData() const { return &_class_data_; } -void HealthAllOkResponse::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.telemetry.HealthAllOkResponse) +void DistanceSensorResponse::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.telemetry.DistanceSensorResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_is_health_all_ok() != 0) { - _this->_internal_set_is_health_all_ok(from._internal_is_health_all_ok()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_distance_sensor()->::mavsdk::rpc::telemetry::DistanceSensor::MergeFrom( + from._internal_distance_sensor()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void HealthAllOkResponse::CopyFrom(const HealthAllOkResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthAllOkResponse) +void DistanceSensorResponse::CopyFrom(const DistanceSensorResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.DistanceSensorResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool HealthAllOkResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool DistanceSensorResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* HealthAllOkResponse::AccessCachedSize() const { +::_pbi::CachedSize* DistanceSensorResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void HealthAllOkResponse::InternalSwap(HealthAllOkResponse* PROTOBUF_RESTRICT other) { +void DistanceSensorResponse::InternalSwap(DistanceSensorResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.is_health_all_ok_, other->_impl_.is_health_all_ok_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.distance_sensor_, other->_impl_.distance_sensor_); } -::google::protobuf::Metadata HealthAllOkResponse::GetMetadata() const { +::google::protobuf::Metadata DistanceSensorResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[57]); } // =================================================================== -class SubscribeUnixEpochTimeRequest::_Internal { +class SubscribeScaledPressureRequest::_Internal { public: }; -SubscribeUnixEpochTimeRequest::SubscribeUnixEpochTimeRequest(::google::protobuf::Arena* arena) +SubscribeScaledPressureRequest::SubscribeScaledPressureRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeScaledPressureRequest) } -SubscribeUnixEpochTimeRequest::SubscribeUnixEpochTimeRequest( +SubscribeScaledPressureRequest::SubscribeScaledPressureRequest( ::google::protobuf::Arena* arena, - const SubscribeUnixEpochTimeRequest& from) + const SubscribeScaledPressureRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeUnixEpochTimeRequest* const _this = this; + SubscribeScaledPressureRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeUnixEpochTimeRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeScaledPressureRequest) } @@ -12120,58 +11829,91 @@ SubscribeUnixEpochTimeRequest::SubscribeUnixEpochTimeRequest( -::google::protobuf::Metadata SubscribeUnixEpochTimeRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeScaledPressureRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[58]); } // =================================================================== -class UnixEpochTimeResponse::_Internal { +class ScaledPressureResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::ScaledPressure& scaled_pressure(const ScaledPressureResponse* msg); + static void set_has_scaled_pressure(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } }; -UnixEpochTimeResponse::UnixEpochTimeResponse(::google::protobuf::Arena* arena) +const ::mavsdk::rpc::telemetry::ScaledPressure& ScaledPressureResponse::_Internal::scaled_pressure(const ScaledPressureResponse* msg) { + return *msg->_impl_.scaled_pressure_; +} +ScaledPressureResponse::ScaledPressureResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.UnixEpochTimeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ScaledPressureResponse) } -UnixEpochTimeResponse::UnixEpochTimeResponse( - ::google::protobuf::Arena* arena, const UnixEpochTimeResponse& from) - : UnixEpochTimeResponse(arena) { - MergeFrom(from); +inline PROTOBUF_NDEBUG_INLINE ScaledPressureResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +ScaledPressureResponse::ScaledPressureResponse( + ::google::protobuf::Arena* arena, + const ScaledPressureResponse& from) + : ::google::protobuf::Message(arena) { + ScaledPressureResponse* 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_.scaled_pressure_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ScaledPressure>(arena, *from._impl_.scaled_pressure_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ScaledPressureResponse) } -inline PROTOBUF_NDEBUG_INLINE UnixEpochTimeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ScaledPressureResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void UnixEpochTimeResponse::SharedCtor(::_pb::Arena* arena) { +inline void ScaledPressureResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.time_us_ = {}; + _impl_.scaled_pressure_ = {}; } -UnixEpochTimeResponse::~UnixEpochTimeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.UnixEpochTimeResponse) +ScaledPressureResponse::~ScaledPressureResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ScaledPressureResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void UnixEpochTimeResponse::SharedDtor() { +inline void ScaledPressureResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.scaled_pressure_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void UnixEpochTimeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) +PROTOBUF_NOINLINE void ScaledPressureResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ScaledPressureResponse) 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_.time_us_ = ::uint64_t{0u}; - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* UnixEpochTimeResponse::_InternalParse( + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.scaled_pressure_ != nullptr); + _impl_.scaled_pressure_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ScaledPressureResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -12179,47 +11921,48 @@ const char* UnixEpochTimeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> UnixEpochTimeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ScaledPressureResponse::_table_ = { { - 0, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _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 - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_UnixEpochTimeResponse_default_instance_._instance, + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_ScaledPressureResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // uint64 time_us = 1; - {::_pbi::TcParser::SingularVarintNoZag1<::uint64_t, offsetof(UnixEpochTimeResponse, _impl_.time_us_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(UnixEpochTimeResponse, _impl_.time_us_)}}, + // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_.scaled_pressure_)}}, }}, {{ 65535, 65535 }}, {{ - // uint64 time_us = 1; - {PROTOBUF_FIELD_OFFSET(UnixEpochTimeResponse, _impl_.time_us_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUInt64)}, - }}, - // no aux_entries - {{ + // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; + {PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_.scaled_pressure_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ScaledPressure>()}, + }}, {{ }}, }; -::uint8_t* UnixEpochTimeResponse::_InternalSerialize( +::uint8_t* ScaledPressureResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ScaledPressureResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // uint64 time_us = 1; - if (this->_internal_time_us() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt64ToArray( - 1, this->_internal_time_us(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::scaled_pressure(this), + _Internal::scaled_pressure(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -12227,94 +11970,97 @@ ::uint8_t* UnixEpochTimeResponse::_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.telemetry.UnixEpochTimeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ScaledPressureResponse) return target; } -::size_t UnixEpochTimeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) +::size_t ScaledPressureResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ScaledPressureResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // uint64 time_us = 1; - if (this->_internal_time_us() != 0) { - total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( - this->_internal_time_us()); + // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.scaled_pressure_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData UnixEpochTimeResponse::_class_data_ = { - UnixEpochTimeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ScaledPressureResponse::_class_data_ = { + ScaledPressureResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* UnixEpochTimeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ScaledPressureResponse::GetClassData() const { return &_class_data_; } -void UnixEpochTimeResponse::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.telemetry.UnixEpochTimeResponse) +void ScaledPressureResponse::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.telemetry.ScaledPressureResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if (from._internal_time_us() != 0) { - _this->_internal_set_time_us(from._internal_time_us()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_scaled_pressure()->::mavsdk::rpc::telemetry::ScaledPressure::MergeFrom( + from._internal_scaled_pressure()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void UnixEpochTimeResponse::CopyFrom(const UnixEpochTimeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.UnixEpochTimeResponse) +void ScaledPressureResponse::CopyFrom(const ScaledPressureResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ScaledPressureResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool UnixEpochTimeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ScaledPressureResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* UnixEpochTimeResponse::AccessCachedSize() const { +::_pbi::CachedSize* ScaledPressureResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void UnixEpochTimeResponse::InternalSwap(UnixEpochTimeResponse* PROTOBUF_RESTRICT other) { +void ScaledPressureResponse::InternalSwap(ScaledPressureResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.time_us_, other->_impl_.time_us_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.scaled_pressure_, other->_impl_.scaled_pressure_); } -::google::protobuf::Metadata UnixEpochTimeResponse::GetMetadata() const { +::google::protobuf::Metadata ScaledPressureResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[59]); } // =================================================================== -class SubscribeDistanceSensorRequest::_Internal { +class SubscribeHeadingRequest::_Internal { public: }; -SubscribeDistanceSensorRequest::SubscribeDistanceSensorRequest(::google::protobuf::Arena* arena) +SubscribeHeadingRequest::SubscribeHeadingRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHeadingRequest) } -SubscribeDistanceSensorRequest::SubscribeDistanceSensorRequest( +SubscribeHeadingRequest::SubscribeHeadingRequest( ::google::protobuf::Arena* arena, - const SubscribeDistanceSensorRequest& from) + const SubscribeHeadingRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeDistanceSensorRequest* const _this = this; + SubscribeHeadingRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeDistanceSensorRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHeadingRequest) } @@ -12325,76 +12071,76 @@ SubscribeDistanceSensorRequest::SubscribeDistanceSensorRequest( -::google::protobuf::Metadata SubscribeDistanceSensorRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeHeadingRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, file_level_metadata_telemetry_2ftelemetry_2eproto[60]); } // =================================================================== -class DistanceSensorResponse::_Internal { +class HeadingResponse::_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(DistanceSensorResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::DistanceSensor& distance_sensor(const DistanceSensorResponse* msg); - static void set_has_distance_sensor(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Heading& heading_deg(const HeadingResponse* msg); + static void set_has_heading_deg(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::DistanceSensor& DistanceSensorResponse::_Internal::distance_sensor(const DistanceSensorResponse* msg) { - return *msg->_impl_.distance_sensor_; +const ::mavsdk::rpc::telemetry::Heading& HeadingResponse::_Internal::heading_deg(const HeadingResponse* msg) { + return *msg->_impl_.heading_deg_; } -DistanceSensorResponse::DistanceSensorResponse(::google::protobuf::Arena* arena) +HeadingResponse::HeadingResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.DistanceSensorResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HeadingResponse) } -inline PROTOBUF_NDEBUG_INLINE DistanceSensorResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE HeadingResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -DistanceSensorResponse::DistanceSensorResponse( +HeadingResponse::HeadingResponse( ::google::protobuf::Arena* arena, - const DistanceSensorResponse& from) + const HeadingResponse& from) : ::google::protobuf::Message(arena) { - DistanceSensorResponse* const _this = this; + HeadingResponse* 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_.distance_sensor_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::DistanceSensor>(arena, *from._impl_.distance_sensor_) + _impl_.heading_deg_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Heading>(arena, *from._impl_.heading_deg_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.DistanceSensorResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HeadingResponse) } -inline PROTOBUF_NDEBUG_INLINE DistanceSensorResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE HeadingResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void DistanceSensorResponse::SharedCtor(::_pb::Arena* arena) { +inline void HeadingResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.distance_sensor_ = {}; + _impl_.heading_deg_ = {}; } -DistanceSensorResponse::~DistanceSensorResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.DistanceSensorResponse) +HeadingResponse::~HeadingResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HeadingResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void DistanceSensorResponse::SharedDtor() { +inline void HeadingResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.distance_sensor_; + delete _impl_.heading_deg_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void DistanceSensorResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.DistanceSensorResponse) +PROTOBUF_NOINLINE void HeadingResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HeadingResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -12402,1305 +12148,14 @@ PROTOBUF_NOINLINE void DistanceSensorResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.distance_sensor_ != nullptr); - _impl_.distance_sensor_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* DistanceSensorResponse::_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> DistanceSensorResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _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), - &_DistanceSensorResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _impl_.distance_sensor_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; - {PROTOBUF_FIELD_OFFSET(DistanceSensorResponse, _impl_.distance_sensor_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::DistanceSensor>()}, - }}, {{ - }}, -}; - -::uint8_t* DistanceSensorResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.DistanceSensorResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.DistanceSensor distance_sensor = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::distance_sensor(this), - _Internal::distance_sensor(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.telemetry.DistanceSensorResponse) - return target; -} - -::size_t DistanceSensorResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.DistanceSensorResponse) - ::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.telemetry.DistanceSensor distance_sensor = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.distance_sensor_); + ABSL_DCHECK(_impl_.heading_deg_ != nullptr); + _impl_.heading_deg_->Clear(); } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData DistanceSensorResponse::_class_data_ = { - DistanceSensorResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* DistanceSensorResponse::GetClassData() const { - return &_class_data_; -} - -void DistanceSensorResponse::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.telemetry.DistanceSensorResponse) - 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_distance_sensor()->::mavsdk::rpc::telemetry::DistanceSensor::MergeFrom( - from._internal_distance_sensor()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void DistanceSensorResponse::CopyFrom(const DistanceSensorResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.DistanceSensorResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool DistanceSensorResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* DistanceSensorResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void DistanceSensorResponse::InternalSwap(DistanceSensorResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.distance_sensor_, other->_impl_.distance_sensor_); -} - -::google::protobuf::Metadata DistanceSensorResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[61]); -} -// =================================================================== - -class SubscribeScaledPressureRequest::_Internal { - public: -}; - -SubscribeScaledPressureRequest::SubscribeScaledPressureRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeScaledPressureRequest) -} -SubscribeScaledPressureRequest::SubscribeScaledPressureRequest( - ::google::protobuf::Arena* arena, - const SubscribeScaledPressureRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeScaledPressureRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeScaledPressureRequest) -} - - - - - - - - - -::google::protobuf::Metadata SubscribeScaledPressureRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[62]); -} -// =================================================================== - -class ScaledPressureResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::ScaledPressure& scaled_pressure(const ScaledPressureResponse* msg); - static void set_has_scaled_pressure(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::telemetry::ScaledPressure& ScaledPressureResponse::_Internal::scaled_pressure(const ScaledPressureResponse* msg) { - return *msg->_impl_.scaled_pressure_; -} -ScaledPressureResponse::ScaledPressureResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.ScaledPressureResponse) -} -inline PROTOBUF_NDEBUG_INLINE ScaledPressureResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -ScaledPressureResponse::ScaledPressureResponse( - ::google::protobuf::Arena* arena, - const ScaledPressureResponse& from) - : ::google::protobuf::Message(arena) { - ScaledPressureResponse* 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_.scaled_pressure_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::ScaledPressure>(arena, *from._impl_.scaled_pressure_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ScaledPressureResponse) -} -inline PROTOBUF_NDEBUG_INLINE ScaledPressureResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void ScaledPressureResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.scaled_pressure_ = {}; -} -ScaledPressureResponse::~ScaledPressureResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ScaledPressureResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void ScaledPressureResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.scaled_pressure_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void ScaledPressureResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ScaledPressureResponse) - 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_.scaled_pressure_ != nullptr); - _impl_.scaled_pressure_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* ScaledPressureResponse::_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> ScaledPressureResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _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), - &_ScaledPressureResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_.scaled_pressure_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; - {PROTOBUF_FIELD_OFFSET(ScaledPressureResponse, _impl_.scaled_pressure_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::ScaledPressure>()}, - }}, {{ - }}, -}; - -::uint8_t* ScaledPressureResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ScaledPressureResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::scaled_pressure(this), - _Internal::scaled_pressure(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.telemetry.ScaledPressureResponse) - return target; -} - -::size_t ScaledPressureResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ScaledPressureResponse) - ::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.telemetry.ScaledPressure scaled_pressure = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.scaled_pressure_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData ScaledPressureResponse::_class_data_ = { - ScaledPressureResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* ScaledPressureResponse::GetClassData() const { - return &_class_data_; -} - -void ScaledPressureResponse::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.telemetry.ScaledPressureResponse) - 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_scaled_pressure()->::mavsdk::rpc::telemetry::ScaledPressure::MergeFrom( - from._internal_scaled_pressure()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void ScaledPressureResponse::CopyFrom(const ScaledPressureResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ScaledPressureResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool ScaledPressureResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* ScaledPressureResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void ScaledPressureResponse::InternalSwap(ScaledPressureResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.scaled_pressure_, other->_impl_.scaled_pressure_); -} - -::google::protobuf::Metadata ScaledPressureResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[63]); -} -// =================================================================== - -class SubscribeHeadingRequest::_Internal { - public: -}; - -SubscribeHeadingRequest::SubscribeHeadingRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeHeadingRequest) -} -SubscribeHeadingRequest::SubscribeHeadingRequest( - ::google::protobuf::Arena* arena, - const SubscribeHeadingRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeHeadingRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHeadingRequest) -} - - - - - - - - - -::google::protobuf::Metadata SubscribeHeadingRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[64]); -} -// =================================================================== - -class HeadingResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Heading& heading_deg(const HeadingResponse* msg); - static void set_has_heading_deg(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::telemetry::Heading& HeadingResponse::_Internal::heading_deg(const HeadingResponse* msg) { - return *msg->_impl_.heading_deg_; -} -HeadingResponse::HeadingResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.HeadingResponse) -} -inline PROTOBUF_NDEBUG_INLINE HeadingResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -HeadingResponse::HeadingResponse( - ::google::protobuf::Arena* arena, - const HeadingResponse& from) - : ::google::protobuf::Message(arena) { - HeadingResponse* 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_.heading_deg_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Heading>(arena, *from._impl_.heading_deg_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HeadingResponse) -} -inline PROTOBUF_NDEBUG_INLINE HeadingResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void HeadingResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.heading_deg_ = {}; -} -HeadingResponse::~HeadingResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HeadingResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void HeadingResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.heading_deg_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void HeadingResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HeadingResponse) - 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_.heading_deg_ != nullptr); - _impl_.heading_deg_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* HeadingResponse::_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> HeadingResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(HeadingResponse, _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), - &_HeadingResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.telemetry.Heading heading_deg = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_.heading_deg_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.telemetry.Heading heading_deg = 1; - {PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_.heading_deg_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Heading>()}, - }}, {{ - }}, -}; - -::uint8_t* HeadingResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HeadingResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Heading heading_deg = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::heading_deg(this), - _Internal::heading_deg(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.telemetry.HeadingResponse) - return target; -} - -::size_t HeadingResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HeadingResponse) - ::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.telemetry.Heading heading_deg = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.heading_deg_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData HeadingResponse::_class_data_ = { - HeadingResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* HeadingResponse::GetClassData() const { - return &_class_data_; -} - -void HeadingResponse::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.telemetry.HeadingResponse) - 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_heading_deg()->::mavsdk::rpc::telemetry::Heading::MergeFrom( - from._internal_heading_deg()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void HeadingResponse::CopyFrom(const HeadingResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HeadingResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool HeadingResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* HeadingResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void HeadingResponse::InternalSwap(HeadingResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.heading_deg_, other->_impl_.heading_deg_); -} - -::google::protobuf::Metadata HeadingResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[65]); -} -// =================================================================== - -class SubscribeAltitudeRequest::_Internal { - public: -}; - -SubscribeAltitudeRequest::SubscribeAltitudeRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) -} -SubscribeAltitudeRequest::SubscribeAltitudeRequest( - ::google::protobuf::Arena* arena, - const SubscribeAltitudeRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeAltitudeRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) -} - - - - - - - - - -::google::protobuf::Metadata SubscribeAltitudeRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[66]); -} -// =================================================================== - -class AltitudeResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::Altitude& altitude(const AltitudeResponse* msg); - static void set_has_altitude(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::telemetry::Altitude& AltitudeResponse::_Internal::altitude(const AltitudeResponse* msg) { - return *msg->_impl_.altitude_; -} -AltitudeResponse::AltitudeResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.AltitudeResponse) -} -inline PROTOBUF_NDEBUG_INLINE AltitudeResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -AltitudeResponse::AltitudeResponse( - ::google::protobuf::Arena* arena, - const AltitudeResponse& from) - : ::google::protobuf::Message(arena) { - AltitudeResponse* 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_.altitude_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Altitude>(arena, *from._impl_.altitude_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.AltitudeResponse) -} -inline PROTOBUF_NDEBUG_INLINE AltitudeResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void AltitudeResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.altitude_ = {}; -} -AltitudeResponse::~AltitudeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.AltitudeResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void AltitudeResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.altitude_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void AltitudeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.AltitudeResponse) - 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_.altitude_ != nullptr); - _impl_.altitude_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* AltitudeResponse::_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> AltitudeResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(AltitudeResponse, _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), - &_AltitudeResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.telemetry.Altitude altitude = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_.altitude_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.telemetry.Altitude altitude = 1; - {PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_.altitude_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Altitude>()}, - }}, {{ - }}, -}; - -::uint8_t* AltitudeResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.AltitudeResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.Altitude altitude = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::altitude(this), - _Internal::altitude(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.telemetry.AltitudeResponse) - return target; -} - -::size_t AltitudeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.AltitudeResponse) - ::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.telemetry.Altitude altitude = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.altitude_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData AltitudeResponse::_class_data_ = { - AltitudeResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* AltitudeResponse::GetClassData() const { - return &_class_data_; -} - -void AltitudeResponse::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.telemetry.AltitudeResponse) - 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_altitude()->::mavsdk::rpc::telemetry::Altitude::MergeFrom( - from._internal_altitude()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void AltitudeResponse::CopyFrom(const AltitudeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.AltitudeResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool AltitudeResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* AltitudeResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void AltitudeResponse::InternalSwap(AltitudeResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.altitude_, other->_impl_.altitude_); -} - -::google::protobuf::Metadata AltitudeResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[67]); -} -// =================================================================== - -class SetRatePositionRequest::_Internal { - public: -}; - -SetRatePositionRequest::SetRatePositionRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRatePositionRequest) -} -SetRatePositionRequest::SetRatePositionRequest( - ::google::protobuf::Arena* arena, const SetRatePositionRequest& from) - : SetRatePositionRequest(arena) { - MergeFrom(from); -} -inline PROTOBUF_NDEBUG_INLINE SetRatePositionRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void SetRatePositionRequest::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.rate_hz_ = {}; -} -SetRatePositionRequest::~SetRatePositionRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRatePositionRequest) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void SetRatePositionRequest::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void SetRatePositionRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRatePositionRequest) - 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_.rate_hz_ = 0; - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* SetRatePositionRequest::_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> SetRatePositionRequest::_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 - &_SetRatePositionRequest_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // double rate_hz = 1; - {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRatePositionRequest, _impl_.rate_hz_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRatePositionRequest, _impl_.rate_hz_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, - }}, - // no aux_entries - {{ - }}, -}; - -::uint8_t* SetRatePositionRequest::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRatePositionRequest) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - // double rate_hz = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = this->_internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 1, this->_internal_rate_hz(), 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.telemetry.SetRatePositionRequest) - return target; -} - -::size_t SetRatePositionRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRatePositionRequest) - ::size_t total_size = 0; - - ::uint32_t cached_has_bits = 0; - // Prevent compiler warnings about cached_has_bits being unused - (void) cached_has_bits; - - // double rate_hz = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = this->_internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - total_size += 9; - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData SetRatePositionRequest::_class_data_ = { - SetRatePositionRequest::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* SetRatePositionRequest::GetClassData() const { - return &_class_data_; -} - -void SetRatePositionRequest::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.telemetry.SetRatePositionRequest) - ABSL_DCHECK_NE(&from, _this); - ::uint32_t cached_has_bits = 0; - (void) cached_has_bits; - - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = from._internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - _this->_internal_set_rate_hz(from._internal_rate_hz()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void SetRatePositionRequest::CopyFrom(const SetRatePositionRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRatePositionRequest) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool SetRatePositionRequest::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* SetRatePositionRequest::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void SetRatePositionRequest::InternalSwap(SetRatePositionRequest* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.rate_hz_, other->_impl_.rate_hz_); -} - -::google::protobuf::Metadata SetRatePositionRequest::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[68]); -} -// =================================================================== - -class SetRatePositionResponse::_Internal { - public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRatePositionResponse* msg); - static void set_has_telemetry_result(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } -}; - -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRatePositionResponse::_Internal::telemetry_result(const SetRatePositionResponse* msg) { - return *msg->_impl_.telemetry_result_; -} -SetRatePositionResponse::SetRatePositionResponse(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRatePositionResponse) -} -inline PROTOBUF_NDEBUG_INLINE SetRatePositionResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from) - : _has_bits_{from._has_bits_}, - _cached_size_{0} {} - -SetRatePositionResponse::SetRatePositionResponse( - ::google::protobuf::Arena* arena, - const SetRatePositionResponse& from) - : ::google::protobuf::Message(arena) { - SetRatePositionResponse* 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_.telemetry_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) - : nullptr; - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRatePositionResponse) -} -inline PROTOBUF_NDEBUG_INLINE SetRatePositionResponse::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void SetRatePositionResponse::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.telemetry_result_ = {}; -} -SetRatePositionResponse::~SetRatePositionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRatePositionResponse) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void SetRatePositionResponse::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.telemetry_result_; - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void SetRatePositionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRatePositionResponse) - 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_.telemetry_result_ != nullptr); - _impl_.telemetry_result_->Clear(); - } - _impl_._has_bits_.Clear(); - _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); -} - -const char* SetRatePositionResponse::_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> SetRatePositionResponse::_table_ = { - { - PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _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), - &_SetRatePositionResponse_default_instance_._instance, - ::_pbi::TcParser::GenericFallback, // fallback - }, {{ - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_.telemetry_result_)}}, - }}, {{ - 65535, 65535 - }}, {{ - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, - }}, {{ - }}, -}; - -::uint8_t* SetRatePositionResponse::_InternalSerialize( - ::uint8_t* target, - ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRatePositionResponse) - ::uint32_t cached_has_bits = 0; - (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::telemetry_result(this), - _Internal::telemetry_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.telemetry.SetRatePositionResponse) - return target; -} - -::size_t SetRatePositionResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRatePositionResponse) - ::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.telemetry.TelemetryResult telemetry_result = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.telemetry_result_); - } - - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); -} - -const ::google::protobuf::Message::ClassData SetRatePositionResponse::_class_data_ = { - SetRatePositionResponse::MergeImpl, - nullptr, // OnDemandRegisterArenaDtor -}; -const ::google::protobuf::Message::ClassData* SetRatePositionResponse::GetClassData() const { - return &_class_data_; -} - -void SetRatePositionResponse::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.telemetry.SetRatePositionResponse) - 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_telemetry_result()->::mavsdk::rpc::telemetry::TelemetryResult::MergeFrom( - from._internal_telemetry_result()); - } - _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); -} - -void SetRatePositionResponse::CopyFrom(const SetRatePositionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRatePositionResponse) - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -PROTOBUF_NOINLINE bool SetRatePositionResponse::IsInitialized() const { - return true; -} - -::_pbi::CachedSize* SetRatePositionResponse::AccessCachedSize() const { - return &_impl_._cached_size_; -} -void SetRatePositionResponse::InternalSwap(SetRatePositionResponse* PROTOBUF_RESTRICT other) { - using std::swap; - _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); -} - -::google::protobuf::Metadata SetRatePositionResponse::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[69]); -} -// =================================================================== - -class SetRateHomeRequest::_Internal { - public: -}; - -SetRateHomeRequest::SetRateHomeRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::Message(arena) { - SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateHomeRequest) -} -SetRateHomeRequest::SetRateHomeRequest( - ::google::protobuf::Arena* arena, const SetRateHomeRequest& from) - : SetRateHomeRequest(arena) { - MergeFrom(from); -} -inline PROTOBUF_NDEBUG_INLINE SetRateHomeRequest::Impl_::Impl_( - ::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena) - : _cached_size_{0} {} - -inline void SetRateHomeRequest::SharedCtor(::_pb::Arena* arena) { - new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.rate_hz_ = {}; -} -SetRateHomeRequest::~SetRateHomeRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateHomeRequest) - _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); - SharedDtor(); -} -inline void SetRateHomeRequest::SharedDtor() { - ABSL_DCHECK(GetArena() == nullptr); - _impl_.~Impl_(); -} - -PROTOBUF_NOINLINE void SetRateHomeRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateHomeRequest) - 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_.rate_hz_ = 0; + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateHomeRequest::_InternalParse( +const char* HeadingResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -13708,52 +12163,48 @@ const char* SetRateHomeRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateHomeRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> HeadingResponse::_table_ = { { - 0, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(HeadingResponse, _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 - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateHomeRequest_default_instance_._instance, + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_HeadingResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // double rate_hz = 1; - {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateHomeRequest, _impl_.rate_hz_)}}, + // .mavsdk.rpc.telemetry.Heading heading_deg = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_.heading_deg_)}}, }}, {{ 65535, 65535 }}, {{ - // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateHomeRequest, _impl_.rate_hz_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, - }}, - // no aux_entries - {{ + // .mavsdk.rpc.telemetry.Heading heading_deg = 1; + {PROTOBUF_FIELD_OFFSET(HeadingResponse, _impl_.heading_deg_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Heading>()}, + }}, {{ }}, }; -::uint8_t* SetRateHomeRequest::_InternalSerialize( +::uint8_t* HeadingResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateHomeRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HeadingResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // double rate_hz = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = this->_internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 1, this->_internal_rate_hz(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry.Heading heading_deg = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::heading_deg(this), + _Internal::heading_deg(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -13761,148 +12212,177 @@ ::uint8_t* SetRateHomeRequest::_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.telemetry.SetRateHomeRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.HeadingResponse) return target; } -::size_t SetRateHomeRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateHomeRequest) +::size_t HeadingResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HeadingResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // double rate_hz = 1; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = this->_internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - total_size += 9; + // .mavsdk.rpc.telemetry.Heading heading_deg = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.heading_deg_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateHomeRequest::_class_data_ = { - SetRateHomeRequest::MergeImpl, +const ::google::protobuf::Message::ClassData HeadingResponse::_class_data_ = { + HeadingResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateHomeRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* HeadingResponse::GetClassData() const { return &_class_data_; } -void SetRateHomeRequest::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.telemetry.SetRateHomeRequest) +void HeadingResponse::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.telemetry.HeadingResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_rate_hz = from._internal_rate_hz(); - ::uint64_t raw_rate_hz; - memcpy(&raw_rate_hz, &tmp_rate_hz, sizeof(tmp_rate_hz)); - if (raw_rate_hz != 0) { - _this->_internal_set_rate_hz(from._internal_rate_hz()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_heading_deg()->::mavsdk::rpc::telemetry::Heading::MergeFrom( + from._internal_heading_deg()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateHomeRequest::CopyFrom(const SetRateHomeRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateHomeRequest) +void HeadingResponse::CopyFrom(const HeadingResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HeadingResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateHomeRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool HeadingResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateHomeRequest::AccessCachedSize() const { +::_pbi::CachedSize* HeadingResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateHomeRequest::InternalSwap(SetRateHomeRequest* PROTOBUF_RESTRICT other) { +void HeadingResponse::InternalSwap(HeadingResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.rate_hz_, other->_impl_.rate_hz_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.heading_deg_, other->_impl_.heading_deg_); } -::google::protobuf::Metadata SetRateHomeRequest::GetMetadata() const { +::google::protobuf::Metadata HeadingResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[70]); + file_level_metadata_telemetry_2ftelemetry_2eproto[61]); } // =================================================================== -class SetRateHomeResponse::_Internal { +class SubscribeAltitudeRequest::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); +}; + +SubscribeAltitudeRequest::SubscribeAltitudeRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) +} +SubscribeAltitudeRequest::SubscribeAltitudeRequest( + ::google::protobuf::Arena* arena, + const SubscribeAltitudeRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeAltitudeRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeAltitudeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, + file_level_metadata_telemetry_2ftelemetry_2eproto[62]); +} +// =================================================================== + +class AltitudeResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateHomeResponse* msg); - static void set_has_telemetry_result(HasBits* has_bits) { + 8 * PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::Altitude& altitude(const AltitudeResponse* msg); + static void set_has_altitude(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateHomeResponse::_Internal::telemetry_result(const SetRateHomeResponse* msg) { - return *msg->_impl_.telemetry_result_; +const ::mavsdk::rpc::telemetry::Altitude& AltitudeResponse::_Internal::altitude(const AltitudeResponse* msg) { + return *msg->_impl_.altitude_; } -SetRateHomeResponse::SetRateHomeResponse(::google::protobuf::Arena* arena) +AltitudeResponse::AltitudeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateHomeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.AltitudeResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateHomeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE AltitudeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateHomeResponse::SetRateHomeResponse( +AltitudeResponse::AltitudeResponse( ::google::protobuf::Arena* arena, - const SetRateHomeResponse& from) + const AltitudeResponse& from) : ::google::protobuf::Message(arena) { - SetRateHomeResponse* const _this = this; + AltitudeResponse* 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_.telemetry_result_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) + _impl_.altitude_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::telemetry::Altitude>(arena, *from._impl_.altitude_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateHomeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.AltitudeResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateHomeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE AltitudeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateHomeResponse::SharedCtor(::_pb::Arena* arena) { +inline void AltitudeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.telemetry_result_ = {}; + _impl_.altitude_ = {}; } -SetRateHomeResponse::~SetRateHomeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateHomeResponse) +AltitudeResponse::~AltitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.AltitudeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateHomeResponse::SharedDtor() { +inline void AltitudeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.telemetry_result_; + delete _impl_.altitude_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateHomeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateHomeResponse) +PROTOBUF_NOINLINE void AltitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.AltitudeResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -13910,14 +12390,14 @@ PROTOBUF_NOINLINE void SetRateHomeResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.telemetry_result_ != nullptr); - _impl_.telemetry_result_->Clear(); + ABSL_DCHECK(_impl_.altitude_ != nullptr); + _impl_.altitude_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateHomeResponse::_InternalParse( +const char* AltitudeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -13925,9 +12405,9 @@ const char* SetRateHomeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateHomeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> AltitudeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -13936,37 +12416,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateHomeResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateHomeResponse_default_instance_._instance, + &_AltitudeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + // .mavsdk.rpc.telemetry.Altitude altitude = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_.altitude_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry.Altitude altitude = 1; + {PROTOBUF_FIELD_OFFSET(AltitudeResponse, _impl_.altitude_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::Altitude>()}, }}, {{ }}, }; -::uint8_t* SetRateHomeResponse::_InternalSerialize( +::uint8_t* AltitudeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateHomeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.AltitudeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + // .mavsdk.rpc.telemetry.Altitude altitude = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::telemetry_result(this), - _Internal::telemetry_result(this).GetCachedSize(), target, stream); + 1, _Internal::altitude(this), + _Internal::altitude(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -13974,114 +12454,114 @@ ::uint8_t* SetRateHomeResponse::_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.telemetry.SetRateHomeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.AltitudeResponse) return target; } -::size_t SetRateHomeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateHomeResponse) +::size_t AltitudeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.AltitudeResponse) ::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.telemetry.TelemetryResult telemetry_result = 1; + // .mavsdk.rpc.telemetry.Altitude altitude = 1; cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.telemetry_result_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.altitude_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateHomeResponse::_class_data_ = { - SetRateHomeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData AltitudeResponse::_class_data_ = { + AltitudeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateHomeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* AltitudeResponse::GetClassData() const { return &_class_data_; } -void SetRateHomeResponse::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.telemetry.SetRateHomeResponse) +void AltitudeResponse::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.telemetry.AltitudeResponse) 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_telemetry_result()->::mavsdk::rpc::telemetry::TelemetryResult::MergeFrom( - from._internal_telemetry_result()); + _this->_internal_mutable_altitude()->::mavsdk::rpc::telemetry::Altitude::MergeFrom( + from._internal_altitude()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateHomeResponse::CopyFrom(const SetRateHomeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateHomeResponse) +void AltitudeResponse::CopyFrom(const AltitudeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.AltitudeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateHomeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool AltitudeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateHomeResponse::AccessCachedSize() const { +::_pbi::CachedSize* AltitudeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateHomeResponse::InternalSwap(SetRateHomeResponse* PROTOBUF_RESTRICT other) { +void AltitudeResponse::InternalSwap(AltitudeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); + swap(_impl_.altitude_, other->_impl_.altitude_); } -::google::protobuf::Metadata SetRateHomeResponse::GetMetadata() const { +::google::protobuf::Metadata AltitudeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[71]); + file_level_metadata_telemetry_2ftelemetry_2eproto[63]); } // =================================================================== -class SetRateInAirRequest::_Internal { +class SetRatePositionRequest::_Internal { public: }; -SetRateInAirRequest::SetRateInAirRequest(::google::protobuf::Arena* arena) +SetRatePositionRequest::SetRatePositionRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateInAirRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRatePositionRequest) } -SetRateInAirRequest::SetRateInAirRequest( - ::google::protobuf::Arena* arena, const SetRateInAirRequest& from) - : SetRateInAirRequest(arena) { +SetRatePositionRequest::SetRatePositionRequest( + ::google::protobuf::Arena* arena, const SetRatePositionRequest& from) + : SetRatePositionRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateInAirRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRatePositionRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateInAirRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRatePositionRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateInAirRequest::~SetRateInAirRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateInAirRequest) +SetRatePositionRequest::~SetRatePositionRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRatePositionRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateInAirRequest::SharedDtor() { +inline void SetRatePositionRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateInAirRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateInAirRequest) +PROTOBUF_NOINLINE void SetRatePositionRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRatePositionRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -14091,7 +12571,7 @@ PROTOBUF_NOINLINE void SetRateInAirRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateInAirRequest::_InternalParse( +const char* SetRatePositionRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -14099,7 +12579,7 @@ const char* SetRateInAirRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateInAirRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRatePositionRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -14110,17 +12590,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateInAirRequest::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateInAirRequest_default_instance_._instance, + &_SetRatePositionRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateInAirRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRatePositionRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateInAirRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRatePositionRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -14128,10 +12608,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateInAirRequest::_table_ = { }}, }; -::uint8_t* SetRateInAirRequest::_InternalSerialize( +::uint8_t* SetRatePositionRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateInAirRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRatePositionRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -14152,12 +12632,12 @@ ::uint8_t* SetRateInAirRequest::_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.telemetry.SetRateInAirRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRatePositionRequest) return target; } -::size_t SetRateInAirRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateInAirRequest) +::size_t SetRatePositionRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRatePositionRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -14177,18 +12657,18 @@ ::size_t SetRateInAirRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateInAirRequest::_class_data_ = { - SetRateInAirRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRatePositionRequest::_class_data_ = { + SetRatePositionRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateInAirRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRatePositionRequest::GetClassData() const { return &_class_data_; } -void SetRateInAirRequest::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.telemetry.SetRateInAirRequest) +void SetRatePositionRequest::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.telemetry.SetRatePositionRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -14204,63 +12684,63 @@ void SetRateInAirRequest::MergeImpl(::google::protobuf::Message& to_msg, const : _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateInAirRequest::CopyFrom(const SetRateInAirRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateInAirRequest) +void SetRatePositionRequest::CopyFrom(const SetRatePositionRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRatePositionRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateInAirRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRatePositionRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateInAirRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRatePositionRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateInAirRequest::InternalSwap(SetRateInAirRequest* PROTOBUF_RESTRICT other) { +void SetRatePositionRequest::InternalSwap(SetRatePositionRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateInAirRequest::GetMetadata() const { +::google::protobuf::Metadata SetRatePositionRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[72]); + file_level_metadata_telemetry_2ftelemetry_2eproto[64]); } // =================================================================== -class SetRateInAirResponse::_Internal { +class SetRatePositionResponse::_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(SetRateInAirResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateInAirResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRatePositionResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateInAirResponse::_Internal::telemetry_result(const SetRateInAirResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRatePositionResponse::_Internal::telemetry_result(const SetRatePositionResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateInAirResponse::SetRateInAirResponse(::google::protobuf::Arena* arena) +SetRatePositionResponse::SetRatePositionResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateInAirResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRatePositionResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateInAirResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRatePositionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateInAirResponse::SetRateInAirResponse( +SetRatePositionResponse::SetRatePositionResponse( ::google::protobuf::Arena* arena, - const SetRateInAirResponse& from) + const SetRatePositionResponse& from) : ::google::protobuf::Message(arena) { - SetRateInAirResponse* const _this = this; + SetRatePositionResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -14270,30 +12750,30 @@ SetRateInAirResponse::SetRateInAirResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateInAirResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRatePositionResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateInAirResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRatePositionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateInAirResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRatePositionResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateInAirResponse::~SetRateInAirResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateInAirResponse) +SetRatePositionResponse::~SetRatePositionResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRatePositionResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateInAirResponse::SharedDtor() { +inline void SetRatePositionResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateInAirResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateInAirResponse) +PROTOBUF_NOINLINE void SetRatePositionResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRatePositionResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -14308,7 +12788,7 @@ PROTOBUF_NOINLINE void SetRateInAirResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateInAirResponse::_InternalParse( +const char* SetRatePositionResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -14316,9 +12796,9 @@ const char* SetRateInAirResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateInAirResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRatePositionResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -14327,17 +12807,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateInAirResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateInAirResponse_default_instance_._instance, + &_SetRatePositionResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRatePositionResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -14345,10 +12825,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateInAirResponse::_table_ = { }}, }; -::uint8_t* SetRateInAirResponse::_InternalSerialize( +::uint8_t* SetRatePositionResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateInAirResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRatePositionResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -14365,12 +12845,12 @@ ::uint8_t* SetRateInAirResponse::_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.telemetry.SetRateInAirResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRatePositionResponse) return target; } -::size_t SetRateInAirResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateInAirResponse) +::size_t SetRatePositionResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRatePositionResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -14387,18 +12867,18 @@ ::size_t SetRateInAirResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateInAirResponse::_class_data_ = { - SetRateInAirResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRatePositionResponse::_class_data_ = { + SetRatePositionResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateInAirResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRatePositionResponse::GetClassData() const { return &_class_data_; } -void SetRateInAirResponse::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.telemetry.SetRateInAirResponse) +void SetRatePositionResponse::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.telemetry.SetRatePositionResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -14410,69 +12890,69 @@ void SetRateInAirResponse::MergeImpl(::google::protobuf::Message& to_msg, const _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateInAirResponse::CopyFrom(const SetRateInAirResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateInAirResponse) +void SetRatePositionResponse::CopyFrom(const SetRatePositionResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRatePositionResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateInAirResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRatePositionResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateInAirResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRatePositionResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateInAirResponse::InternalSwap(SetRateInAirResponse* PROTOBUF_RESTRICT other) { +void SetRatePositionResponse::InternalSwap(SetRatePositionResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateInAirResponse::GetMetadata() const { +::google::protobuf::Metadata SetRatePositionResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[73]); + file_level_metadata_telemetry_2ftelemetry_2eproto[65]); } // =================================================================== -class SetRateLandedStateRequest::_Internal { +class SetRateHomeRequest::_Internal { public: }; -SetRateLandedStateRequest::SetRateLandedStateRequest(::google::protobuf::Arena* arena) +SetRateHomeRequest::SetRateHomeRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateLandedStateRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateHomeRequest) } -SetRateLandedStateRequest::SetRateLandedStateRequest( - ::google::protobuf::Arena* arena, const SetRateLandedStateRequest& from) - : SetRateLandedStateRequest(arena) { +SetRateHomeRequest::SetRateHomeRequest( + ::google::protobuf::Arena* arena, const SetRateHomeRequest& from) + : SetRateHomeRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateHomeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateLandedStateRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateHomeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateLandedStateRequest::~SetRateLandedStateRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateLandedStateRequest) +SetRateHomeRequest::~SetRateHomeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateHomeRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateLandedStateRequest::SharedDtor() { +inline void SetRateHomeRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateLandedStateRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) +PROTOBUF_NOINLINE void SetRateHomeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateHomeRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -14482,7 +12962,7 @@ PROTOBUF_NOINLINE void SetRateLandedStateRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateLandedStateRequest::_InternalParse( +const char* SetRateHomeRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -14490,7 +12970,7 @@ const char* SetRateLandedStateRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateLandedStateRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateHomeRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -14501,17 +12981,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateLandedStateRequest::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateLandedStateRequest_default_instance_._instance, + &_SetRateHomeRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateLandedStateRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateHomeRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateLandedStateRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateHomeRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -14519,10 +12999,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateLandedStateRequest::_table_ = { }}, }; -::uint8_t* SetRateLandedStateRequest::_InternalSerialize( +::uint8_t* SetRateHomeRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateHomeRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -14543,12 +13023,12 @@ ::uint8_t* SetRateLandedStateRequest::_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.telemetry.SetRateLandedStateRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateHomeRequest) return target; } -::size_t SetRateLandedStateRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) +::size_t SetRateHomeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateHomeRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -14568,18 +13048,18 @@ ::size_t SetRateLandedStateRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateLandedStateRequest::_class_data_ = { - SetRateLandedStateRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateHomeRequest::_class_data_ = { + SetRateHomeRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateLandedStateRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateHomeRequest::GetClassData() const { return &_class_data_; } -void SetRateLandedStateRequest::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.telemetry.SetRateLandedStateRequest) +void SetRateHomeRequest::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.telemetry.SetRateHomeRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -14595,63 +13075,63 @@ void SetRateLandedStateRequest::MergeImpl(::google::protobuf::Message& to_msg, c _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateLandedStateRequest::CopyFrom(const SetRateLandedStateRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) +void SetRateHomeRequest::CopyFrom(const SetRateHomeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateHomeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateLandedStateRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateHomeRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateLandedStateRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateHomeRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateLandedStateRequest::InternalSwap(SetRateLandedStateRequest* PROTOBUF_RESTRICT other) { +void SetRateHomeRequest::InternalSwap(SetRateHomeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateLandedStateRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateHomeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[74]); + file_level_metadata_telemetry_2ftelemetry_2eproto[66]); } // =================================================================== -class SetRateLandedStateResponse::_Internal { +class SetRateHomeResponse::_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(SetRateLandedStateResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateLandedStateResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateHomeResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateLandedStateResponse::_Internal::telemetry_result(const SetRateLandedStateResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateHomeResponse::_Internal::telemetry_result(const SetRateHomeResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateLandedStateResponse::SetRateLandedStateResponse(::google::protobuf::Arena* arena) +SetRateHomeResponse::SetRateHomeResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateHomeResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateHomeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateLandedStateResponse::SetRateLandedStateResponse( +SetRateHomeResponse::SetRateHomeResponse( ::google::protobuf::Arena* arena, - const SetRateLandedStateResponse& from) + const SetRateHomeResponse& from) : ::google::protobuf::Message(arena) { - SetRateLandedStateResponse* const _this = this; + SetRateHomeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -14661,30 +13141,30 @@ SetRateLandedStateResponse::SetRateLandedStateResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateHomeResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateHomeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateLandedStateResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateHomeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateLandedStateResponse::~SetRateLandedStateResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) +SetRateHomeResponse::~SetRateHomeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateHomeResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateLandedStateResponse::SharedDtor() { +inline void SetRateHomeResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateLandedStateResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) +PROTOBUF_NOINLINE void SetRateHomeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateHomeResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -14699,7 +13179,7 @@ PROTOBUF_NOINLINE void SetRateLandedStateResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateLandedStateResponse::_InternalParse( +const char* SetRateHomeResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -14707,9 +13187,9 @@ const char* SetRateLandedStateResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateLandedStateResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateHomeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -14718,17 +13198,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateLandedStateResponse::_table_ = 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateLandedStateResponse_default_instance_._instance, + &_SetRateHomeResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateHomeResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -14736,10 +13216,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateLandedStateResponse::_table_ = }}, }; -::uint8_t* SetRateLandedStateResponse::_InternalSerialize( +::uint8_t* SetRateHomeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateHomeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -14756,12 +13236,12 @@ ::uint8_t* SetRateLandedStateResponse::_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.telemetry.SetRateLandedStateResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateHomeResponse) return target; } -::size_t SetRateLandedStateResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) +::size_t SetRateHomeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateHomeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -14778,18 +13258,18 @@ ::size_t SetRateLandedStateResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateLandedStateResponse::_class_data_ = { - SetRateLandedStateResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateHomeResponse::_class_data_ = { + SetRateHomeResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateLandedStateResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateHomeResponse::GetClassData() const { return &_class_data_; } -void SetRateLandedStateResponse::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.telemetry.SetRateLandedStateResponse) +void SetRateHomeResponse::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.telemetry.SetRateHomeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -14801,69 +13281,69 @@ void SetRateLandedStateResponse::MergeImpl(::google::protobuf::Message& to_msg, _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateLandedStateResponse::CopyFrom(const SetRateLandedStateResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) +void SetRateHomeResponse::CopyFrom(const SetRateHomeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateHomeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateLandedStateResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateHomeResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateLandedStateResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateHomeResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateLandedStateResponse::InternalSwap(SetRateLandedStateResponse* PROTOBUF_RESTRICT other) { +void SetRateHomeResponse::InternalSwap(SetRateHomeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateLandedStateResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateHomeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[75]); + file_level_metadata_telemetry_2ftelemetry_2eproto[67]); } // =================================================================== -class SetRateVtolStateRequest::_Internal { +class SetRateInAirRequest::_Internal { public: }; -SetRateVtolStateRequest::SetRateVtolStateRequest(::google::protobuf::Arena* arena) +SetRateInAirRequest::SetRateInAirRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateVtolStateRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateInAirRequest) } -SetRateVtolStateRequest::SetRateVtolStateRequest( - ::google::protobuf::Arena* arena, const SetRateVtolStateRequest& from) - : SetRateVtolStateRequest(arena) { +SetRateInAirRequest::SetRateInAirRequest( + ::google::protobuf::Arena* arena, const SetRateInAirRequest& from) + : SetRateInAirRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateInAirRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateVtolStateRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateInAirRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateVtolStateRequest::~SetRateVtolStateRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateVtolStateRequest) +SetRateInAirRequest::~SetRateInAirRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateInAirRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateVtolStateRequest::SharedDtor() { +inline void SetRateInAirRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateVtolStateRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) +PROTOBUF_NOINLINE void SetRateInAirRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateInAirRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -14873,7 +13353,7 @@ PROTOBUF_NOINLINE void SetRateVtolStateRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateVtolStateRequest::_InternalParse( +const char* SetRateInAirRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -14881,7 +13361,7 @@ const char* SetRateVtolStateRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateVtolStateRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateInAirRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -14892,17 +13372,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateVtolStateRequest::_table_ = { 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateVtolStateRequest_default_instance_._instance, + &_SetRateInAirRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateVtolStateRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateInAirRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateVtolStateRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateInAirRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -14910,10 +13390,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateVtolStateRequest::_table_ = { }}, }; -::uint8_t* SetRateVtolStateRequest::_InternalSerialize( +::uint8_t* SetRateInAirRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateInAirRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -14934,12 +13414,12 @@ ::uint8_t* SetRateVtolStateRequest::_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.telemetry.SetRateVtolStateRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateInAirRequest) return target; } -::size_t SetRateVtolStateRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) +::size_t SetRateInAirRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateInAirRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -14959,18 +13439,18 @@ ::size_t SetRateVtolStateRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateVtolStateRequest::_class_data_ = { - SetRateVtolStateRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateInAirRequest::_class_data_ = { + SetRateInAirRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateVtolStateRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateInAirRequest::GetClassData() const { return &_class_data_; } -void SetRateVtolStateRequest::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.telemetry.SetRateVtolStateRequest) +void SetRateInAirRequest::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.telemetry.SetRateInAirRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -14986,63 +13466,63 @@ void SetRateVtolStateRequest::MergeImpl(::google::protobuf::Message& to_msg, con _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateVtolStateRequest::CopyFrom(const SetRateVtolStateRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) +void SetRateInAirRequest::CopyFrom(const SetRateInAirRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateInAirRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateVtolStateRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateInAirRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateVtolStateRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateInAirRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateVtolStateRequest::InternalSwap(SetRateVtolStateRequest* PROTOBUF_RESTRICT other) { +void SetRateInAirRequest::InternalSwap(SetRateInAirRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateVtolStateRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateInAirRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[76]); + file_level_metadata_telemetry_2ftelemetry_2eproto[68]); } // =================================================================== -class SetRateVtolStateResponse::_Internal { +class SetRateInAirResponse::_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(SetRateVtolStateResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateVtolStateResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateInAirResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateVtolStateResponse::_Internal::telemetry_result(const SetRateVtolStateResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateInAirResponse::_Internal::telemetry_result(const SetRateInAirResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateVtolStateResponse::SetRateVtolStateResponse(::google::protobuf::Arena* arena) +SetRateInAirResponse::SetRateInAirResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateInAirResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateInAirResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateVtolStateResponse::SetRateVtolStateResponse( +SetRateInAirResponse::SetRateInAirResponse( ::google::protobuf::Arena* arena, - const SetRateVtolStateResponse& from) + const SetRateInAirResponse& from) : ::google::protobuf::Message(arena) { - SetRateVtolStateResponse* const _this = this; + SetRateInAirResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -15052,30 +13532,30 @@ SetRateVtolStateResponse::SetRateVtolStateResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateInAirResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateInAirResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateVtolStateResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateInAirResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateVtolStateResponse::~SetRateVtolStateResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) +SetRateInAirResponse::~SetRateInAirResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateInAirResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateVtolStateResponse::SharedDtor() { +inline void SetRateInAirResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateVtolStateResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) +PROTOBUF_NOINLINE void SetRateInAirResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateInAirResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -15090,7 +13570,7 @@ PROTOBUF_NOINLINE void SetRateVtolStateResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateVtolStateResponse::_InternalParse( +const char* SetRateInAirResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -15098,9 +13578,9 @@ const char* SetRateVtolStateResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateVtolStateResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateInAirResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -15109,17 +13589,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateVtolStateResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateVtolStateResponse_default_instance_._instance, + &_SetRateInAirResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateInAirResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -15127,10 +13607,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateVtolStateResponse::_table_ = { }}, }; -::uint8_t* SetRateVtolStateResponse::_InternalSerialize( +::uint8_t* SetRateInAirResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateInAirResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -15147,12 +13627,12 @@ ::uint8_t* SetRateVtolStateResponse::_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.telemetry.SetRateVtolStateResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateInAirResponse) return target; } -::size_t SetRateVtolStateResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) +::size_t SetRateInAirResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateInAirResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -15169,18 +13649,18 @@ ::size_t SetRateVtolStateResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateVtolStateResponse::_class_data_ = { - SetRateVtolStateResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateInAirResponse::_class_data_ = { + SetRateInAirResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateVtolStateResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateInAirResponse::GetClassData() const { return &_class_data_; } -void SetRateVtolStateResponse::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.telemetry.SetRateVtolStateResponse) +void SetRateInAirResponse::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.telemetry.SetRateInAirResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -15192,69 +13672,69 @@ void SetRateVtolStateResponse::MergeImpl(::google::protobuf::Message& to_msg, co _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateVtolStateResponse::CopyFrom(const SetRateVtolStateResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) +void SetRateInAirResponse::CopyFrom(const SetRateInAirResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateInAirResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateVtolStateResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateInAirResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateVtolStateResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateInAirResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateVtolStateResponse::InternalSwap(SetRateVtolStateResponse* PROTOBUF_RESTRICT other) { +void SetRateInAirResponse::InternalSwap(SetRateInAirResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateVtolStateResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateInAirResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[77]); + file_level_metadata_telemetry_2ftelemetry_2eproto[69]); } // =================================================================== -class SetRateAttitudeEulerRequest::_Internal { +class SetRateLandedStateRequest::_Internal { public: }; -SetRateAttitudeEulerRequest::SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena) +SetRateLandedStateRequest::SetRateLandedStateRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) -} -SetRateAttitudeEulerRequest::SetRateAttitudeEulerRequest( - ::google::protobuf::Arena* arena, const SetRateAttitudeEulerRequest& from) - : SetRateAttitudeEulerRequest(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateLandedStateRequest) +} +SetRateLandedStateRequest::SetRateLandedStateRequest( + ::google::protobuf::Arena* arena, const SetRateLandedStateRequest& from) + : SetRateLandedStateRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeEulerRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateLandedStateRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateAttitudeEulerRequest::~SetRateAttitudeEulerRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) +SetRateLandedStateRequest::~SetRateLandedStateRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateLandedStateRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeEulerRequest::SharedDtor() { +inline void SetRateLandedStateRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeEulerRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) +PROTOBUF_NOINLINE void SetRateLandedStateRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -15264,7 +13744,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeEulerRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeEulerRequest::_InternalParse( +const char* SetRateLandedStateRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -15272,7 +13752,7 @@ const char* SetRateAttitudeEulerRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeEulerRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateLandedStateRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -15283,17 +13763,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeEulerRequest::_table_ = 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateAttitudeEulerRequest_default_instance_._instance, + &_SetRateLandedStateRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateLandedStateRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateLandedStateRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -15301,10 +13781,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeEulerRequest::_table_ = }}, }; -::uint8_t* SetRateAttitudeEulerRequest::_InternalSerialize( +::uint8_t* SetRateLandedStateRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -15325,12 +13805,12 @@ ::uint8_t* SetRateAttitudeEulerRequest::_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.telemetry.SetRateAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateLandedStateRequest) return target; } -::size_t SetRateAttitudeEulerRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) +::size_t SetRateLandedStateRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -15350,18 +13830,18 @@ ::size_t SetRateAttitudeEulerRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeEulerRequest::_class_data_ = { - SetRateAttitudeEulerRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateLandedStateRequest::_class_data_ = { + SetRateLandedStateRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeEulerRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateLandedStateRequest::GetClassData() const { return &_class_data_; } -void SetRateAttitudeEulerRequest::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.telemetry.SetRateAttitudeEulerRequest) +void SetRateLandedStateRequest::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.telemetry.SetRateLandedStateRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -15377,63 +13857,63 @@ void SetRateAttitudeEulerRequest::MergeImpl(::google::protobuf::Message& to_msg, _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeEulerRequest::CopyFrom(const SetRateAttitudeEulerRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) +void SetRateLandedStateRequest::CopyFrom(const SetRateLandedStateRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateLandedStateRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeEulerRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateLandedStateRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeEulerRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateLandedStateRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeEulerRequest::InternalSwap(SetRateAttitudeEulerRequest* PROTOBUF_RESTRICT other) { +void SetRateLandedStateRequest::InternalSwap(SetRateLandedStateRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateAttitudeEulerRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateLandedStateRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[78]); + file_level_metadata_telemetry_2ftelemetry_2eproto[70]); } // =================================================================== -class SetRateAttitudeEulerResponse::_Internal { +class SetRateLandedStateResponse::_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(SetRateAttitudeEulerResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeEulerResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateLandedStateResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeEulerResponse::_Internal::telemetry_result(const SetRateAttitudeEulerResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateLandedStateResponse::_Internal::telemetry_result(const SetRateLandedStateResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateAttitudeEulerResponse::SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena) +SetRateLandedStateResponse::SetRateLandedStateResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateAttitudeEulerResponse::SetRateAttitudeEulerResponse( +SetRateLandedStateResponse::SetRateLandedStateResponse( ::google::protobuf::Arena* arena, - const SetRateAttitudeEulerResponse& from) + const SetRateLandedStateResponse& from) : ::google::protobuf::Message(arena) { - SetRateAttitudeEulerResponse* const _this = this; + SetRateLandedStateResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -15443,30 +13923,30 @@ SetRateAttitudeEulerResponse::SetRateAttitudeEulerResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateLandedStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeEulerResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateLandedStateResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateAttitudeEulerResponse::~SetRateAttitudeEulerResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) +SetRateLandedStateResponse::~SetRateLandedStateResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateLandedStateResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeEulerResponse::SharedDtor() { +inline void SetRateLandedStateResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeEulerResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) +PROTOBUF_NOINLINE void SetRateLandedStateResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -15481,7 +13961,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeEulerResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeEulerResponse::_InternalParse( +const char* SetRateLandedStateResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -15489,9 +13969,9 @@ const char* SetRateAttitudeEulerResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeEulerResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateLandedStateResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -15500,17 +13980,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeEulerResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateAttitudeEulerResponse_default_instance_._instance, + &_SetRateLandedStateResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateLandedStateResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -15518,10 +13998,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeEulerResponse::_table_ }}, }; -::uint8_t* SetRateAttitudeEulerResponse::_InternalSerialize( +::uint8_t* SetRateLandedStateResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -15538,12 +14018,12 @@ ::uint8_t* SetRateAttitudeEulerResponse::_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.telemetry.SetRateAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateLandedStateResponse) return target; } -::size_t SetRateAttitudeEulerResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) +::size_t SetRateLandedStateResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -15560,18 +14040,18 @@ ::size_t SetRateAttitudeEulerResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeEulerResponse::_class_data_ = { - SetRateAttitudeEulerResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateLandedStateResponse::_class_data_ = { + SetRateLandedStateResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeEulerResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateLandedStateResponse::GetClassData() const { return &_class_data_; } -void SetRateAttitudeEulerResponse::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.telemetry.SetRateAttitudeEulerResponse) +void SetRateLandedStateResponse::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.telemetry.SetRateLandedStateResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -15583,69 +14063,69 @@ void SetRateAttitudeEulerResponse::MergeImpl(::google::protobuf::Message& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeEulerResponse::CopyFrom(const SetRateAttitudeEulerResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) +void SetRateLandedStateResponse::CopyFrom(const SetRateLandedStateResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateLandedStateResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeEulerResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateLandedStateResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeEulerResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateLandedStateResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeEulerResponse::InternalSwap(SetRateAttitudeEulerResponse* PROTOBUF_RESTRICT other) { +void SetRateLandedStateResponse::InternalSwap(SetRateLandedStateResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateAttitudeEulerResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateLandedStateResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[79]); + file_level_metadata_telemetry_2ftelemetry_2eproto[71]); } // =================================================================== -class SetRateAttitudeQuaternionRequest::_Internal { +class SetRateVtolStateRequest::_Internal { public: }; -SetRateAttitudeQuaternionRequest::SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena) +SetRateVtolStateRequest::SetRateVtolStateRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateVtolStateRequest) } -SetRateAttitudeQuaternionRequest::SetRateAttitudeQuaternionRequest( - ::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionRequest& from) - : SetRateAttitudeQuaternionRequest(arena) { +SetRateVtolStateRequest::SetRateVtolStateRequest( + ::google::protobuf::Arena* arena, const SetRateVtolStateRequest& from) + : SetRateVtolStateRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeQuaternionRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateVtolStateRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateAttitudeQuaternionRequest::~SetRateAttitudeQuaternionRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) +SetRateVtolStateRequest::~SetRateVtolStateRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateVtolStateRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeQuaternionRequest::SharedDtor() { +inline void SetRateVtolStateRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeQuaternionRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) +PROTOBUF_NOINLINE void SetRateVtolStateRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -15655,7 +14135,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeQuaternionRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeQuaternionRequest::_InternalParse( +const char* SetRateVtolStateRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -15663,7 +14143,7 @@ const char* SetRateAttitudeQuaternionRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeQuaternionRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateVtolStateRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -15674,17 +14154,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeQuaternionRequest::_tab 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateAttitudeQuaternionRequest_default_instance_._instance, + &_SetRateVtolStateRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateVtolStateRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateVtolStateRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -15692,10 +14172,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeQuaternionRequest::_tab }}, }; -::uint8_t* SetRateAttitudeQuaternionRequest::_InternalSerialize( +::uint8_t* SetRateVtolStateRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -15716,12 +14196,12 @@ ::uint8_t* SetRateAttitudeQuaternionRequest::_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.telemetry.SetRateAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateVtolStateRequest) return target; } -::size_t SetRateAttitudeQuaternionRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) +::size_t SetRateVtolStateRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -15741,18 +14221,18 @@ ::size_t SetRateAttitudeQuaternionRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeQuaternionRequest::_class_data_ = { - SetRateAttitudeQuaternionRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateVtolStateRequest::_class_data_ = { + SetRateVtolStateRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeQuaternionRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateVtolStateRequest::GetClassData() const { return &_class_data_; } -void SetRateAttitudeQuaternionRequest::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.telemetry.SetRateAttitudeQuaternionRequest) +void SetRateVtolStateRequest::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.telemetry.SetRateVtolStateRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -15768,63 +14248,63 @@ void SetRateAttitudeQuaternionRequest::MergeImpl(::google::protobuf::Message& to _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeQuaternionRequest::CopyFrom(const SetRateAttitudeQuaternionRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) +void SetRateVtolStateRequest::CopyFrom(const SetRateVtolStateRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateVtolStateRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeQuaternionRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateVtolStateRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeQuaternionRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateVtolStateRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeQuaternionRequest::InternalSwap(SetRateAttitudeQuaternionRequest* PROTOBUF_RESTRICT other) { +void SetRateVtolStateRequest::InternalSwap(SetRateVtolStateRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateAttitudeQuaternionRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateVtolStateRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[80]); + file_level_metadata_telemetry_2ftelemetry_2eproto[72]); } // =================================================================== -class SetRateAttitudeQuaternionResponse::_Internal { +class SetRateVtolStateResponse::_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(SetRateAttitudeQuaternionResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeQuaternionResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateVtolStateResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeQuaternionResponse::_Internal::telemetry_result(const SetRateAttitudeQuaternionResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateVtolStateResponse::_Internal::telemetry_result(const SetRateVtolStateResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateAttitudeQuaternionResponse::SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena) +SetRateVtolStateResponse::SetRateVtolStateResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateAttitudeQuaternionResponse::SetRateAttitudeQuaternionResponse( +SetRateVtolStateResponse::SetRateVtolStateResponse( ::google::protobuf::Arena* arena, - const SetRateAttitudeQuaternionResponse& from) + const SetRateVtolStateResponse& from) : ::google::protobuf::Message(arena) { - SetRateAttitudeQuaternionResponse* const _this = this; + SetRateVtolStateResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -15834,30 +14314,30 @@ SetRateAttitudeQuaternionResponse::SetRateAttitudeQuaternionResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateVtolStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeQuaternionResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateVtolStateResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateAttitudeQuaternionResponse::~SetRateAttitudeQuaternionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) +SetRateVtolStateResponse::~SetRateVtolStateResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateVtolStateResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeQuaternionResponse::SharedDtor() { +inline void SetRateVtolStateResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeQuaternionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) +PROTOBUF_NOINLINE void SetRateVtolStateResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -15872,7 +14352,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeQuaternionResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeQuaternionResponse::_InternalParse( +const char* SetRateVtolStateResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -15880,9 +14360,9 @@ const char* SetRateAttitudeQuaternionResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeQuaternionResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateVtolStateResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -15891,17 +14371,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeQuaternionResponse::_ta 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateAttitudeQuaternionResponse_default_instance_._instance, + &_SetRateVtolStateResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateVtolStateResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -15909,10 +14389,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeQuaternionResponse::_ta }}, }; -::uint8_t* SetRateAttitudeQuaternionResponse::_InternalSerialize( +::uint8_t* SetRateVtolStateResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -15929,12 +14409,12 @@ ::uint8_t* SetRateAttitudeQuaternionResponse::_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.telemetry.SetRateAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateVtolStateResponse) return target; } -::size_t SetRateAttitudeQuaternionResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) +::size_t SetRateVtolStateResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -15951,18 +14431,18 @@ ::size_t SetRateAttitudeQuaternionResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeQuaternionResponse::_class_data_ = { - SetRateAttitudeQuaternionResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateVtolStateResponse::_class_data_ = { + SetRateVtolStateResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeQuaternionResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateVtolStateResponse::GetClassData() const { return &_class_data_; } -void SetRateAttitudeQuaternionResponse::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.telemetry.SetRateAttitudeQuaternionResponse) +void SetRateVtolStateResponse::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.telemetry.SetRateVtolStateResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -15974,69 +14454,69 @@ void SetRateAttitudeQuaternionResponse::MergeImpl(::google::protobuf::Message& t _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeQuaternionResponse::CopyFrom(const SetRateAttitudeQuaternionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) +void SetRateVtolStateResponse::CopyFrom(const SetRateVtolStateResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateVtolStateResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeQuaternionResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateVtolStateResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeQuaternionResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateVtolStateResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeQuaternionResponse::InternalSwap(SetRateAttitudeQuaternionResponse* PROTOBUF_RESTRICT other) { +void SetRateVtolStateResponse::InternalSwap(SetRateVtolStateResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateAttitudeQuaternionResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateVtolStateResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[81]); + file_level_metadata_telemetry_2ftelemetry_2eproto[73]); } // =================================================================== -class SetRateAttitudeAngularVelocityBodyRequest::_Internal { +class SetRateAttitudeEulerRequest::_Internal { public: }; -SetRateAttitudeAngularVelocityBodyRequest::SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena) +SetRateAttitudeEulerRequest::SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) } -SetRateAttitudeAngularVelocityBodyRequest::SetRateAttitudeAngularVelocityBodyRequest( - ::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyRequest& from) - : SetRateAttitudeAngularVelocityBodyRequest(arena) { +SetRateAttitudeEulerRequest::SetRateAttitudeEulerRequest( + ::google::protobuf::Arena* arena, const SetRateAttitudeEulerRequest& from) + : SetRateAttitudeEulerRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeAngularVelocityBodyRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeEulerRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateAttitudeAngularVelocityBodyRequest::~SetRateAttitudeAngularVelocityBodyRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) +SetRateAttitudeEulerRequest::~SetRateAttitudeEulerRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeAngularVelocityBodyRequest::SharedDtor() { +inline void SetRateAttitudeEulerRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) +PROTOBUF_NOINLINE void SetRateAttitudeEulerRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -16046,7 +14526,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeAngularVelocityBodyRequest::_InternalParse( +const char* SetRateAttitudeEulerRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -16054,7 +14534,7 @@ const char* SetRateAttitudeAngularVelocityBodyRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeAngularVelocityBodyRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeEulerRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -16065,17 +14545,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeAngularVelocityBodyRequ 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateAttitudeAngularVelocityBodyRequest_default_instance_._instance, + &_SetRateAttitudeEulerRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -16083,10 +14563,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeAngularVelocityBodyRequ }}, }; -::uint8_t* SetRateAttitudeAngularVelocityBodyRequest::_InternalSerialize( +::uint8_t* SetRateAttitudeEulerRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -16107,12 +14587,12 @@ ::uint8_t* SetRateAttitudeAngularVelocityBodyRequest::_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.telemetry.SetRateAttitudeAngularVelocityBodyRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) return target; } -::size_t SetRateAttitudeAngularVelocityBodyRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) +::size_t SetRateAttitudeEulerRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -16132,18 +14612,18 @@ ::size_t SetRateAttitudeAngularVelocityBodyRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeAngularVelocityBodyRequest::_class_data_ = { - SetRateAttitudeAngularVelocityBodyRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeEulerRequest::_class_data_ = { + SetRateAttitudeEulerRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeAngularVelocityBodyRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeEulerRequest::GetClassData() const { return &_class_data_; } -void SetRateAttitudeAngularVelocityBodyRequest::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.telemetry.SetRateAttitudeAngularVelocityBodyRequest) +void SetRateAttitudeEulerRequest::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.telemetry.SetRateAttitudeEulerRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -16159,63 +14639,63 @@ void SetRateAttitudeAngularVelocityBodyRequest::MergeImpl(::google::protobuf::Me _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeAngularVelocityBodyRequest::CopyFrom(const SetRateAttitudeAngularVelocityBodyRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) +void SetRateAttitudeEulerRequest::CopyFrom(const SetRateAttitudeEulerRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeAngularVelocityBodyRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeEulerRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeAngularVelocityBodyRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeEulerRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeAngularVelocityBodyRequest::InternalSwap(SetRateAttitudeAngularVelocityBodyRequest* PROTOBUF_RESTRICT other) { +void SetRateAttitudeEulerRequest::InternalSwap(SetRateAttitudeEulerRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateAttitudeAngularVelocityBodyRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeEulerRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[82]); + file_level_metadata_telemetry_2ftelemetry_2eproto[74]); } // =================================================================== -class SetRateAttitudeAngularVelocityBodyResponse::_Internal { +class SetRateAttitudeEulerResponse::_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(SetRateAttitudeAngularVelocityBodyResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeAngularVelocityBodyResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeEulerResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeAngularVelocityBodyResponse::_Internal::telemetry_result(const SetRateAttitudeAngularVelocityBodyResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeEulerResponse::_Internal::telemetry_result(const SetRateAttitudeEulerResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateAttitudeAngularVelocityBodyResponse::SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena) +SetRateAttitudeEulerResponse::SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateAttitudeAngularVelocityBodyResponse::SetRateAttitudeAngularVelocityBodyResponse( +SetRateAttitudeEulerResponse::SetRateAttitudeEulerResponse( ::google::protobuf::Arena* arena, - const SetRateAttitudeAngularVelocityBodyResponse& from) + const SetRateAttitudeEulerResponse& from) : ::google::protobuf::Message(arena) { - SetRateAttitudeAngularVelocityBodyResponse* const _this = this; + SetRateAttitudeEulerResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -16225,30 +14705,30 @@ SetRateAttitudeAngularVelocityBodyResponse::SetRateAttitudeAngularVelocityBodyRe ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeEulerResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateAttitudeAngularVelocityBodyResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeEulerResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateAttitudeAngularVelocityBodyResponse::~SetRateAttitudeAngularVelocityBodyResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) +SetRateAttitudeEulerResponse::~SetRateAttitudeEulerResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateAttitudeAngularVelocityBodyResponse::SharedDtor() { +inline void SetRateAttitudeEulerResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) +PROTOBUF_NOINLINE void SetRateAttitudeEulerResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -16263,7 +14743,7 @@ PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateAttitudeAngularVelocityBodyResponse::_InternalParse( +const char* SetRateAttitudeEulerResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -16271,9 +14751,9 @@ const char* SetRateAttitudeAngularVelocityBodyResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeAngularVelocityBodyResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeEulerResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -16282,17 +14762,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeAngularVelocityBodyResp 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateAttitudeAngularVelocityBodyResponse_default_instance_._instance, + &_SetRateAttitudeEulerResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeEulerResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -16300,10 +14780,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeAngularVelocityBodyResp }}, }; -::uint8_t* SetRateAttitudeAngularVelocityBodyResponse::_InternalSerialize( +::uint8_t* SetRateAttitudeEulerResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -16320,12 +14800,12 @@ ::uint8_t* SetRateAttitudeAngularVelocityBodyResponse::_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.telemetry.SetRateAttitudeAngularVelocityBodyResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) return target; } -::size_t SetRateAttitudeAngularVelocityBodyResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) +::size_t SetRateAttitudeEulerResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -16342,18 +14822,18 @@ ::size_t SetRateAttitudeAngularVelocityBodyResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateAttitudeAngularVelocityBodyResponse::_class_data_ = { - SetRateAttitudeAngularVelocityBodyResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeEulerResponse::_class_data_ = { + SetRateAttitudeEulerResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateAttitudeAngularVelocityBodyResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeEulerResponse::GetClassData() const { return &_class_data_; } -void SetRateAttitudeAngularVelocityBodyResponse::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.telemetry.SetRateAttitudeAngularVelocityBodyResponse) +void SetRateAttitudeEulerResponse::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.telemetry.SetRateAttitudeEulerResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -16365,69 +14845,69 @@ void SetRateAttitudeAngularVelocityBodyResponse::MergeImpl(::google::protobuf::M _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateAttitudeAngularVelocityBodyResponse::CopyFrom(const SetRateAttitudeAngularVelocityBodyResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) +void SetRateAttitudeEulerResponse::CopyFrom(const SetRateAttitudeEulerResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateAttitudeAngularVelocityBodyResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeEulerResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateAttitudeAngularVelocityBodyResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeEulerResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateAttitudeAngularVelocityBodyResponse::InternalSwap(SetRateAttitudeAngularVelocityBodyResponse* PROTOBUF_RESTRICT other) { +void SetRateAttitudeEulerResponse::InternalSwap(SetRateAttitudeEulerResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateAttitudeAngularVelocityBodyResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeEulerResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[83]); + file_level_metadata_telemetry_2ftelemetry_2eproto[75]); } // =================================================================== -class SetRateCameraAttitudeQuaternionRequest::_Internal { +class SetRateAttitudeQuaternionRequest::_Internal { public: }; -SetRateCameraAttitudeQuaternionRequest::SetRateCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena) +SetRateAttitudeQuaternionRequest::SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) } -SetRateCameraAttitudeQuaternionRequest::SetRateCameraAttitudeQuaternionRequest( - ::google::protobuf::Arena* arena, const SetRateCameraAttitudeQuaternionRequest& from) - : SetRateCameraAttitudeQuaternionRequest(arena) { +SetRateAttitudeQuaternionRequest::SetRateAttitudeQuaternionRequest( + ::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionRequest& from) + : SetRateAttitudeQuaternionRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeQuaternionRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateCameraAttitudeQuaternionRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeQuaternionRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateCameraAttitudeQuaternionRequest::~SetRateCameraAttitudeQuaternionRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) +SetRateAttitudeQuaternionRequest::~SetRateAttitudeQuaternionRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateCameraAttitudeQuaternionRequest::SharedDtor() { +inline void SetRateAttitudeQuaternionRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateCameraAttitudeQuaternionRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) +PROTOBUF_NOINLINE void SetRateAttitudeQuaternionRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -16437,7 +14917,7 @@ PROTOBUF_NOINLINE void SetRateCameraAttitudeQuaternionRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateCameraAttitudeQuaternionRequest::_InternalParse( +const char* SetRateAttitudeQuaternionRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -16445,7 +14925,7 @@ const char* SetRateCameraAttitudeQuaternionRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeQuaternionRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeQuaternionRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -16456,17 +14936,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeQuaternionRequest 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateCameraAttitudeQuaternionRequest_default_instance_._instance, + &_SetRateAttitudeQuaternionRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeQuaternionRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeQuaternionRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -16474,10 +14954,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeQuaternionRequest }}, }; -::uint8_t* SetRateCameraAttitudeQuaternionRequest::_InternalSerialize( +::uint8_t* SetRateAttitudeQuaternionRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -16498,12 +14978,12 @@ ::uint8_t* SetRateCameraAttitudeQuaternionRequest::_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.telemetry.SetRateCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) return target; } -::size_t SetRateCameraAttitudeQuaternionRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) +::size_t SetRateAttitudeQuaternionRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -16523,18 +15003,18 @@ ::size_t SetRateCameraAttitudeQuaternionRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateCameraAttitudeQuaternionRequest::_class_data_ = { - SetRateCameraAttitudeQuaternionRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeQuaternionRequest::_class_data_ = { + SetRateAttitudeQuaternionRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateCameraAttitudeQuaternionRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeQuaternionRequest::GetClassData() const { return &_class_data_; } -void SetRateCameraAttitudeQuaternionRequest::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.telemetry.SetRateCameraAttitudeQuaternionRequest) +void SetRateAttitudeQuaternionRequest::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.telemetry.SetRateAttitudeQuaternionRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -16550,63 +15030,63 @@ void SetRateCameraAttitudeQuaternionRequest::MergeImpl(::google::protobuf::Messa _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateCameraAttitudeQuaternionRequest::CopyFrom(const SetRateCameraAttitudeQuaternionRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) +void SetRateAttitudeQuaternionRequest::CopyFrom(const SetRateAttitudeQuaternionRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateCameraAttitudeQuaternionRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeQuaternionRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateCameraAttitudeQuaternionRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeQuaternionRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateCameraAttitudeQuaternionRequest::InternalSwap(SetRateCameraAttitudeQuaternionRequest* PROTOBUF_RESTRICT other) { +void SetRateAttitudeQuaternionRequest::InternalSwap(SetRateAttitudeQuaternionRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateCameraAttitudeQuaternionRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeQuaternionRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[84]); + file_level_metadata_telemetry_2ftelemetry_2eproto[76]); } // =================================================================== -class SetRateCameraAttitudeQuaternionResponse::_Internal { +class SetRateAttitudeQuaternionResponse::_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(SetRateCameraAttitudeQuaternionResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateCameraAttitudeQuaternionResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeQuaternionResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeQuaternionResponse::_Internal::telemetry_result(const SetRateCameraAttitudeQuaternionResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeQuaternionResponse::_Internal::telemetry_result(const SetRateAttitudeQuaternionResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateCameraAttitudeQuaternionResponse::SetRateCameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena) +SetRateAttitudeQuaternionResponse::SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateCameraAttitudeQuaternionResponse::SetRateCameraAttitudeQuaternionResponse( +SetRateAttitudeQuaternionResponse::SetRateAttitudeQuaternionResponse( ::google::protobuf::Arena* arena, - const SetRateCameraAttitudeQuaternionResponse& from) + const SetRateAttitudeQuaternionResponse& from) : ::google::protobuf::Message(arena) { - SetRateCameraAttitudeQuaternionResponse* const _this = this; + SetRateAttitudeQuaternionResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -16616,30 +15096,30 @@ SetRateCameraAttitudeQuaternionResponse::SetRateCameraAttitudeQuaternionResponse ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeQuaternionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeQuaternionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateCameraAttitudeQuaternionResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeQuaternionResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateCameraAttitudeQuaternionResponse::~SetRateCameraAttitudeQuaternionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) +SetRateAttitudeQuaternionResponse::~SetRateAttitudeQuaternionResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateCameraAttitudeQuaternionResponse::SharedDtor() { +inline void SetRateAttitudeQuaternionResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateCameraAttitudeQuaternionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) +PROTOBUF_NOINLINE void SetRateAttitudeQuaternionResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -16654,7 +15134,7 @@ PROTOBUF_NOINLINE void SetRateCameraAttitudeQuaternionResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateCameraAttitudeQuaternionResponse::_InternalParse( +const char* SetRateAttitudeQuaternionResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -16662,9 +15142,9 @@ const char* SetRateCameraAttitudeQuaternionResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeQuaternionResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeQuaternionResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeQuaternionResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -16673,17 +15153,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeQuaternionRespons 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateCameraAttitudeQuaternionResponse_default_instance_._instance, + &_SetRateAttitudeQuaternionResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeQuaternionResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeQuaternionResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeQuaternionResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -16691,10 +15171,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeQuaternionRespons }}, }; -::uint8_t* SetRateCameraAttitudeQuaternionResponse::_InternalSerialize( +::uint8_t* SetRateAttitudeQuaternionResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -16711,12 +15191,12 @@ ::uint8_t* SetRateCameraAttitudeQuaternionResponse::_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.telemetry.SetRateCameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) return target; } -::size_t SetRateCameraAttitudeQuaternionResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) +::size_t SetRateAttitudeQuaternionResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -16733,18 +15213,18 @@ ::size_t SetRateCameraAttitudeQuaternionResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateCameraAttitudeQuaternionResponse::_class_data_ = { - SetRateCameraAttitudeQuaternionResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeQuaternionResponse::_class_data_ = { + SetRateAttitudeQuaternionResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateCameraAttitudeQuaternionResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeQuaternionResponse::GetClassData() const { return &_class_data_; } -void SetRateCameraAttitudeQuaternionResponse::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.telemetry.SetRateCameraAttitudeQuaternionResponse) +void SetRateAttitudeQuaternionResponse::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.telemetry.SetRateAttitudeQuaternionResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -16756,69 +15236,69 @@ void SetRateCameraAttitudeQuaternionResponse::MergeImpl(::google::protobuf::Mess _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateCameraAttitudeQuaternionResponse::CopyFrom(const SetRateCameraAttitudeQuaternionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) +void SetRateAttitudeQuaternionResponse::CopyFrom(const SetRateAttitudeQuaternionResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateCameraAttitudeQuaternionResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeQuaternionResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateCameraAttitudeQuaternionResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeQuaternionResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateCameraAttitudeQuaternionResponse::InternalSwap(SetRateCameraAttitudeQuaternionResponse* PROTOBUF_RESTRICT other) { +void SetRateAttitudeQuaternionResponse::InternalSwap(SetRateAttitudeQuaternionResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateCameraAttitudeQuaternionResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeQuaternionResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[85]); + file_level_metadata_telemetry_2ftelemetry_2eproto[77]); } // =================================================================== -class SetRateCameraAttitudeRequest::_Internal { +class SetRateAttitudeAngularVelocityBodyRequest::_Internal { public: }; -SetRateCameraAttitudeRequest::SetRateCameraAttitudeRequest(::google::protobuf::Arena* arena) +SetRateAttitudeAngularVelocityBodyRequest::SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) } -SetRateCameraAttitudeRequest::SetRateCameraAttitudeRequest( - ::google::protobuf::Arena* arena, const SetRateCameraAttitudeRequest& from) - : SetRateCameraAttitudeRequest(arena) { +SetRateAttitudeAngularVelocityBodyRequest::SetRateAttitudeAngularVelocityBodyRequest( + ::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyRequest& from) + : SetRateAttitudeAngularVelocityBodyRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeRequest::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateCameraAttitudeRequest::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeAngularVelocityBodyRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.rate_hz_ = {}; } -SetRateCameraAttitudeRequest::~SetRateCameraAttitudeRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) +SetRateAttitudeAngularVelocityBodyRequest::~SetRateAttitudeAngularVelocityBodyRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateCameraAttitudeRequest::SharedDtor() { +inline void SetRateAttitudeAngularVelocityBodyRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateCameraAttitudeRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) +PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -16828,7 +15308,7 @@ PROTOBUF_NOINLINE void SetRateCameraAttitudeRequest::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateCameraAttitudeRequest::_InternalParse( +const char* SetRateAttitudeAngularVelocityBodyRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -16836,7 +15316,7 @@ const char* SetRateCameraAttitudeRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeRequest::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateAttitudeAngularVelocityBodyRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ @@ -16847,17 +15327,17 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeRequest::_table_ 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_SetRateCameraAttitudeRequest_default_instance_._instance, + &_SetRateAttitudeAngularVelocityBodyRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // double rate_hz = 1; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeRequest, _impl_.rate_hz_)}}, + {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyRequest, _impl_.rate_hz_)}}, }}, {{ 65535, 65535 }}, {{ // double rate_hz = 1; - {PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeRequest, _impl_.rate_hz_), 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyRequest, _impl_.rate_hz_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, }}, // no aux_entries @@ -16865,10 +15345,10 @@ const ::_pbi::TcParseTable<0, 1, 0, 0, 2> SetRateCameraAttitudeRequest::_table_ }}, }; -::uint8_t* SetRateCameraAttitudeRequest::_InternalSerialize( +::uint8_t* SetRateAttitudeAngularVelocityBodyRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -16889,12 +15369,12 @@ ::uint8_t* SetRateCameraAttitudeRequest::_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.telemetry.SetRateCameraAttitudeRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) return target; } -::size_t SetRateCameraAttitudeRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) +::size_t SetRateAttitudeAngularVelocityBodyRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -16914,18 +15394,18 @@ ::size_t SetRateCameraAttitudeRequest::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateCameraAttitudeRequest::_class_data_ = { - SetRateCameraAttitudeRequest::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeAngularVelocityBodyRequest::_class_data_ = { + SetRateAttitudeAngularVelocityBodyRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateCameraAttitudeRequest::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeAngularVelocityBodyRequest::GetClassData() const { return &_class_data_; } -void SetRateCameraAttitudeRequest::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.telemetry.SetRateCameraAttitudeRequest) +void SetRateAttitudeAngularVelocityBodyRequest::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.telemetry.SetRateAttitudeAngularVelocityBodyRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -16941,63 +15421,63 @@ void SetRateCameraAttitudeRequest::MergeImpl(::google::protobuf::Message& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateCameraAttitudeRequest::CopyFrom(const SetRateCameraAttitudeRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) +void SetRateAttitudeAngularVelocityBodyRequest::CopyFrom(const SetRateAttitudeAngularVelocityBodyRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateCameraAttitudeRequest::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeAngularVelocityBodyRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateCameraAttitudeRequest::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeAngularVelocityBodyRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateCameraAttitudeRequest::InternalSwap(SetRateCameraAttitudeRequest* PROTOBUF_RESTRICT other) { +void SetRateAttitudeAngularVelocityBodyRequest::InternalSwap(SetRateAttitudeAngularVelocityBodyRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_.rate_hz_, other->_impl_.rate_hz_); } -::google::protobuf::Metadata SetRateCameraAttitudeRequest::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeAngularVelocityBodyRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[86]); + file_level_metadata_telemetry_2ftelemetry_2eproto[78]); } // =================================================================== -class SetRateCameraAttitudeResponse::_Internal { +class SetRateAttitudeAngularVelocityBodyResponse::_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(SetRateCameraAttitudeResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateCameraAttitudeResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAttitudeAngularVelocityBodyResponse* msg); static void set_has_telemetry_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeResponse::_Internal::telemetry_result(const SetRateCameraAttitudeResponse* msg) { +const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAttitudeAngularVelocityBodyResponse::_Internal::telemetry_result(const SetRateAttitudeAngularVelocityBodyResponse* msg) { return *msg->_impl_.telemetry_result_; } -SetRateCameraAttitudeResponse::SetRateCameraAttitudeResponse(::google::protobuf::Arena* arena) +SetRateAttitudeAngularVelocityBodyResponse::SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -SetRateCameraAttitudeResponse::SetRateCameraAttitudeResponse( +SetRateAttitudeAngularVelocityBodyResponse::SetRateAttitudeAngularVelocityBodyResponse( ::google::protobuf::Arena* arena, - const SetRateCameraAttitudeResponse& from) + const SetRateAttitudeAngularVelocityBodyResponse& from) : ::google::protobuf::Message(arena) { - SetRateCameraAttitudeResponse* const _this = this; + SetRateAttitudeAngularVelocityBodyResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -17007,30 +15487,30 @@ SetRateCameraAttitudeResponse::SetRateCameraAttitudeResponse( ? CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(arena, *from._impl_.telemetry_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) } -inline PROTOBUF_NDEBUG_INLINE SetRateCameraAttitudeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE SetRateAttitudeAngularVelocityBodyResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void SetRateCameraAttitudeResponse::SharedCtor(::_pb::Arena* arena) { +inline void SetRateAttitudeAngularVelocityBodyResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_result_ = {}; } -SetRateCameraAttitudeResponse::~SetRateCameraAttitudeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) +SetRateAttitudeAngularVelocityBodyResponse::~SetRateAttitudeAngularVelocityBodyResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void SetRateCameraAttitudeResponse::SharedDtor() { +inline void SetRateAttitudeAngularVelocityBodyResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.telemetry_result_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void SetRateCameraAttitudeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) +PROTOBUF_NOINLINE void SetRateAttitudeAngularVelocityBodyResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -17045,7 +15525,7 @@ PROTOBUF_NOINLINE void SetRateCameraAttitudeResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* SetRateCameraAttitudeResponse::_InternalParse( +const char* SetRateAttitudeAngularVelocityBodyResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -17053,9 +15533,9 @@ const char* SetRateCameraAttitudeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateAttitudeAngularVelocityBodyResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -17064,17 +15544,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeResponse::_table_ 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_SetRateCameraAttitudeResponse_default_instance_._instance, + &_SetRateAttitudeAngularVelocityBodyResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeResponse, _impl_.telemetry_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_.telemetry_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - {PROTOBUF_FIELD_OFFSET(SetRateCameraAttitudeResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(SetRateAttitudeAngularVelocityBodyResponse, _impl_.telemetry_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry::TelemetryResult>()}, @@ -17082,10 +15562,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> SetRateCameraAttitudeResponse::_table_ }}, }; -::uint8_t* SetRateCameraAttitudeResponse::_InternalSerialize( +::uint8_t* SetRateAttitudeAngularVelocityBodyResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -17102,12 +15582,12 @@ ::uint8_t* SetRateCameraAttitudeResponse::_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.telemetry.SetRateCameraAttitudeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) return target; } -::size_t SetRateCameraAttitudeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) +::size_t SetRateAttitudeAngularVelocityBodyResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -17124,18 +15604,18 @@ ::size_t SetRateCameraAttitudeResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData SetRateCameraAttitudeResponse::_class_data_ = { - SetRateCameraAttitudeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData SetRateAttitudeAngularVelocityBodyResponse::_class_data_ = { + SetRateAttitudeAngularVelocityBodyResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* SetRateCameraAttitudeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* SetRateAttitudeAngularVelocityBodyResponse::GetClassData() const { return &_class_data_; } -void SetRateCameraAttitudeResponse::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.telemetry.SetRateCameraAttitudeResponse) +void SetRateAttitudeAngularVelocityBodyResponse::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.telemetry.SetRateAttitudeAngularVelocityBodyResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -17147,31 +15627,31 @@ void SetRateCameraAttitudeResponse::MergeImpl(::google::protobuf::Message& to_ms _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void SetRateCameraAttitudeResponse::CopyFrom(const SetRateCameraAttitudeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) +void SetRateAttitudeAngularVelocityBodyResponse::CopyFrom(const SetRateAttitudeAngularVelocityBodyResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool SetRateCameraAttitudeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool SetRateAttitudeAngularVelocityBodyResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* SetRateCameraAttitudeResponse::AccessCachedSize() const { +::_pbi::CachedSize* SetRateAttitudeAngularVelocityBodyResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void SetRateCameraAttitudeResponse::InternalSwap(SetRateCameraAttitudeResponse* PROTOBUF_RESTRICT other) { +void SetRateAttitudeAngularVelocityBodyResponse::InternalSwap(SetRateAttitudeAngularVelocityBodyResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_result_, other->_impl_.telemetry_result_); } -::google::protobuf::Metadata SetRateCameraAttitudeResponse::GetMetadata() const { +::google::protobuf::Metadata SetRateAttitudeAngularVelocityBodyResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[87]); + file_level_metadata_telemetry_2ftelemetry_2eproto[79]); } // =================================================================== @@ -17355,7 +15835,7 @@ void SetRateVelocityNedRequest::InternalSwap(SetRateVelocityNedRequest* PROTOBUF ::google::protobuf::Metadata SetRateVelocityNedRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[88]); + file_level_metadata_telemetry_2ftelemetry_2eproto[80]); } // =================================================================== @@ -17562,7 +16042,7 @@ void SetRateVelocityNedResponse::InternalSwap(SetRateVelocityNedResponse* PROTOB ::google::protobuf::Metadata SetRateVelocityNedResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[89]); + file_level_metadata_telemetry_2ftelemetry_2eproto[81]); } // =================================================================== @@ -17746,7 +16226,7 @@ void SetRateGpsInfoRequest::InternalSwap(SetRateGpsInfoRequest* PROTOBUF_RESTRIC ::google::protobuf::Metadata SetRateGpsInfoRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[90]); + file_level_metadata_telemetry_2ftelemetry_2eproto[82]); } // =================================================================== @@ -17953,7 +16433,7 @@ void SetRateGpsInfoResponse::InternalSwap(SetRateGpsInfoResponse* PROTOBUF_RESTR ::google::protobuf::Metadata SetRateGpsInfoResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[91]); + file_level_metadata_telemetry_2ftelemetry_2eproto[83]); } // =================================================================== @@ -18137,7 +16617,7 @@ void SetRateRawGpsRequest::InternalSwap(SetRateRawGpsRequest* PROTOBUF_RESTRICT ::google::protobuf::Metadata SetRateRawGpsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[92]); + file_level_metadata_telemetry_2ftelemetry_2eproto[84]); } // =================================================================== @@ -18321,7 +16801,7 @@ void SetRateBatteryRequest::InternalSwap(SetRateBatteryRequest* PROTOBUF_RESTRIC ::google::protobuf::Metadata SetRateBatteryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[93]); + file_level_metadata_telemetry_2ftelemetry_2eproto[85]); } // =================================================================== @@ -18528,7 +17008,7 @@ void SetRateBatteryResponse::InternalSwap(SetRateBatteryResponse* PROTOBUF_RESTR ::google::protobuf::Metadata SetRateBatteryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[94]); + file_level_metadata_telemetry_2ftelemetry_2eproto[86]); } // =================================================================== @@ -18712,7 +17192,7 @@ void SetRateRcStatusRequest::InternalSwap(SetRateRcStatusRequest* PROTOBUF_RESTR ::google::protobuf::Metadata SetRateRcStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[95]); + file_level_metadata_telemetry_2ftelemetry_2eproto[87]); } // =================================================================== @@ -18919,7 +17399,7 @@ void SetRateRcStatusResponse::InternalSwap(SetRateRcStatusResponse* PROTOBUF_RES ::google::protobuf::Metadata SetRateRcStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[96]); + file_level_metadata_telemetry_2ftelemetry_2eproto[88]); } // =================================================================== @@ -19103,7 +17583,7 @@ void SetRateActuatorControlTargetRequest::InternalSwap(SetRateActuatorControlTar ::google::protobuf::Metadata SetRateActuatorControlTargetRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[97]); + file_level_metadata_telemetry_2ftelemetry_2eproto[89]); } // =================================================================== @@ -19310,7 +17790,7 @@ void SetRateActuatorControlTargetResponse::InternalSwap(SetRateActuatorControlTa ::google::protobuf::Metadata SetRateActuatorControlTargetResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[98]); + file_level_metadata_telemetry_2ftelemetry_2eproto[90]); } // =================================================================== @@ -19494,7 +17974,7 @@ void SetRateActuatorOutputStatusRequest::InternalSwap(SetRateActuatorOutputStatu ::google::protobuf::Metadata SetRateActuatorOutputStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[99]); + file_level_metadata_telemetry_2ftelemetry_2eproto[91]); } // =================================================================== @@ -19701,7 +18181,7 @@ void SetRateActuatorOutputStatusResponse::InternalSwap(SetRateActuatorOutputStat ::google::protobuf::Metadata SetRateActuatorOutputStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[100]); + file_level_metadata_telemetry_2ftelemetry_2eproto[92]); } // =================================================================== @@ -19885,7 +18365,7 @@ void SetRateOdometryRequest::InternalSwap(SetRateOdometryRequest* PROTOBUF_RESTR ::google::protobuf::Metadata SetRateOdometryRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[101]); + file_level_metadata_telemetry_2ftelemetry_2eproto[93]); } // =================================================================== @@ -20092,7 +18572,7 @@ void SetRateOdometryResponse::InternalSwap(SetRateOdometryResponse* PROTOBUF_RES ::google::protobuf::Metadata SetRateOdometryResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[102]); + file_level_metadata_telemetry_2ftelemetry_2eproto[94]); } // =================================================================== @@ -20276,7 +18756,7 @@ void SetRatePositionVelocityNedRequest::InternalSwap(SetRatePositionVelocityNedR ::google::protobuf::Metadata SetRatePositionVelocityNedRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[103]); + file_level_metadata_telemetry_2ftelemetry_2eproto[95]); } // =================================================================== @@ -20483,7 +18963,7 @@ void SetRatePositionVelocityNedResponse::InternalSwap(SetRatePositionVelocityNed ::google::protobuf::Metadata SetRatePositionVelocityNedResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[104]); + file_level_metadata_telemetry_2ftelemetry_2eproto[96]); } // =================================================================== @@ -20667,7 +19147,7 @@ void SetRateGroundTruthRequest::InternalSwap(SetRateGroundTruthRequest* PROTOBUF ::google::protobuf::Metadata SetRateGroundTruthRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[105]); + file_level_metadata_telemetry_2ftelemetry_2eproto[97]); } // =================================================================== @@ -20874,7 +19354,7 @@ void SetRateGroundTruthResponse::InternalSwap(SetRateGroundTruthResponse* PROTOB ::google::protobuf::Metadata SetRateGroundTruthResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[106]); + file_level_metadata_telemetry_2ftelemetry_2eproto[98]); } // =================================================================== @@ -21058,7 +19538,7 @@ void SetRateFixedwingMetricsRequest::InternalSwap(SetRateFixedwingMetricsRequest ::google::protobuf::Metadata SetRateFixedwingMetricsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[107]); + file_level_metadata_telemetry_2ftelemetry_2eproto[99]); } // =================================================================== @@ -21265,7 +19745,7 @@ void SetRateFixedwingMetricsResponse::InternalSwap(SetRateFixedwingMetricsRespon ::google::protobuf::Metadata SetRateFixedwingMetricsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[108]); + file_level_metadata_telemetry_2ftelemetry_2eproto[100]); } // =================================================================== @@ -21449,7 +19929,7 @@ void SetRateImuRequest::InternalSwap(SetRateImuRequest* PROTOBUF_RESTRICT other) ::google::protobuf::Metadata SetRateImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[109]); + file_level_metadata_telemetry_2ftelemetry_2eproto[101]); } // =================================================================== @@ -21656,7 +20136,7 @@ void SetRateImuResponse::InternalSwap(SetRateImuResponse* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata SetRateImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[110]); + file_level_metadata_telemetry_2ftelemetry_2eproto[102]); } // =================================================================== @@ -21840,7 +20320,7 @@ void SetRateScaledImuRequest::InternalSwap(SetRateScaledImuRequest* PROTOBUF_RES ::google::protobuf::Metadata SetRateScaledImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[111]); + file_level_metadata_telemetry_2ftelemetry_2eproto[103]); } // =================================================================== @@ -22047,7 +20527,7 @@ void SetRateScaledImuResponse::InternalSwap(SetRateScaledImuResponse* PROTOBUF_R ::google::protobuf::Metadata SetRateScaledImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[112]); + file_level_metadata_telemetry_2ftelemetry_2eproto[104]); } // =================================================================== @@ -22231,7 +20711,7 @@ void SetRateRawImuRequest::InternalSwap(SetRateRawImuRequest* PROTOBUF_RESTRICT ::google::protobuf::Metadata SetRateRawImuRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[113]); + file_level_metadata_telemetry_2ftelemetry_2eproto[105]); } // =================================================================== @@ -22438,7 +20918,7 @@ void SetRateRawImuResponse::InternalSwap(SetRateRawImuResponse* PROTOBUF_RESTRIC ::google::protobuf::Metadata SetRateRawImuResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[114]); + file_level_metadata_telemetry_2ftelemetry_2eproto[106]); } // =================================================================== @@ -22622,7 +21102,7 @@ void SetRateUnixEpochTimeRequest::InternalSwap(SetRateUnixEpochTimeRequest* PROT ::google::protobuf::Metadata SetRateUnixEpochTimeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[115]); + file_level_metadata_telemetry_2ftelemetry_2eproto[107]); } // =================================================================== @@ -22829,7 +21309,7 @@ void SetRateUnixEpochTimeResponse::InternalSwap(SetRateUnixEpochTimeResponse* PR ::google::protobuf::Metadata SetRateUnixEpochTimeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[116]); + file_level_metadata_telemetry_2ftelemetry_2eproto[108]); } // =================================================================== @@ -23013,7 +21493,7 @@ void SetRateDistanceSensorRequest::InternalSwap(SetRateDistanceSensorRequest* PR ::google::protobuf::Metadata SetRateDistanceSensorRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[117]); + file_level_metadata_telemetry_2ftelemetry_2eproto[109]); } // =================================================================== @@ -23220,7 +21700,7 @@ void SetRateDistanceSensorResponse::InternalSwap(SetRateDistanceSensorResponse* ::google::protobuf::Metadata SetRateDistanceSensorResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[118]); + file_level_metadata_telemetry_2ftelemetry_2eproto[110]); } // =================================================================== @@ -23255,7 +21735,7 @@ GetGpsGlobalOriginRequest::GetGpsGlobalOriginRequest( ::google::protobuf::Metadata GetGpsGlobalOriginRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[119]); + file_level_metadata_telemetry_2ftelemetry_2eproto[111]); } // =================================================================== @@ -23518,7 +21998,7 @@ void GetGpsGlobalOriginResponse::InternalSwap(GetGpsGlobalOriginResponse* PROTOB ::google::protobuf::Metadata GetGpsGlobalOriginResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[120]); + file_level_metadata_telemetry_2ftelemetry_2eproto[112]); } // =================================================================== @@ -23702,7 +22182,7 @@ void SetRateAltitudeRequest::InternalSwap(SetRateAltitudeRequest* PROTOBUF_RESTR ::google::protobuf::Metadata SetRateAltitudeRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[121]); + file_level_metadata_telemetry_2ftelemetry_2eproto[113]); } // =================================================================== @@ -23909,7 +22389,7 @@ void SetRateAltitudeResponse::InternalSwap(SetRateAltitudeResponse* PROTOBUF_RES ::google::protobuf::Metadata SetRateAltitudeResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[122]); + file_level_metadata_telemetry_2ftelemetry_2eproto[114]); } // =================================================================== @@ -24213,7 +22693,7 @@ void Position::InternalSwap(Position* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Position::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[123]); + file_level_metadata_telemetry_2ftelemetry_2eproto[115]); } // =================================================================== @@ -24397,7 +22877,7 @@ void Heading::InternalSwap(Heading* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Heading::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[124]); + file_level_metadata_telemetry_2ftelemetry_2eproto[116]); } // =================================================================== @@ -24726,7 +23206,7 @@ void Quaternion::InternalSwap(Quaternion* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Quaternion::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[125]); + file_level_metadata_telemetry_2ftelemetry_2eproto[117]); } // =================================================================== @@ -25016,7 +23496,7 @@ void EulerAngle::InternalSwap(EulerAngle* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata EulerAngle::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[126]); + file_level_metadata_telemetry_2ftelemetry_2eproto[118]); } // =================================================================== @@ -25285,7 +23765,7 @@ void AngularVelocityBody::InternalSwap(AngularVelocityBody* PROTOBUF_RESTRICT ot ::google::protobuf::Metadata AngularVelocityBody::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[127]); + file_level_metadata_telemetry_2ftelemetry_2eproto[119]); } // =================================================================== @@ -25489,7 +23969,7 @@ void GpsInfo::InternalSwap(GpsInfo* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata GpsInfo::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[128]); + file_level_metadata_telemetry_2ftelemetry_2eproto[120]); } // =================================================================== @@ -26141,7 +24621,7 @@ void RawGps::InternalSwap(RawGps* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata RawGps::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[129]); + file_level_metadata_telemetry_2ftelemetry_2eproto[121]); } // =================================================================== @@ -26505,7 +24985,7 @@ void Battery::InternalSwap(Battery* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Battery::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[130]); + file_level_metadata_telemetry_2ftelemetry_2eproto[122]); } // =================================================================== @@ -26813,7 +25293,7 @@ void Health::InternalSwap(Health* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Health::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[131]); + file_level_metadata_telemetry_2ftelemetry_2eproto[123]); } // =================================================================== @@ -27052,7 +25532,7 @@ void RcStatus::InternalSwap(RcStatus* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata RcStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[132]); + file_level_metadata_telemetry_2ftelemetry_2eproto[124]); } // =================================================================== @@ -27268,7 +25748,7 @@ void StatusText::InternalSwap(StatusText* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata StatusText::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[133]); + file_level_metadata_telemetry_2ftelemetry_2eproto[125]); } // =================================================================== @@ -27479,7 +25959,7 @@ void ActuatorControlTarget::InternalSwap(ActuatorControlTarget* PROTOBUF_RESTRIC ::google::protobuf::Metadata ActuatorControlTarget::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[134]); + file_level_metadata_telemetry_2ftelemetry_2eproto[126]); } // =================================================================== @@ -27690,7 +26170,7 @@ void ActuatorOutputStatus::InternalSwap(ActuatorOutputStatus* PROTOBUF_RESTRICT ::google::protobuf::Metadata ActuatorOutputStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[135]); + file_level_metadata_telemetry_2ftelemetry_2eproto[127]); } // =================================================================== @@ -27875,7 +26355,7 @@ void Covariance::InternalSwap(Covariance* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Covariance::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[136]); + file_level_metadata_telemetry_2ftelemetry_2eproto[128]); } // =================================================================== @@ -28144,7 +26624,7 @@ void VelocityBody::InternalSwap(VelocityBody* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata VelocityBody::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[137]); + file_level_metadata_telemetry_2ftelemetry_2eproto[129]); } // =================================================================== @@ -28413,7 +26893,7 @@ void PositionBody::InternalSwap(PositionBody* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata PositionBody::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[138]); + file_level_metadata_telemetry_2ftelemetry_2eproto[130]); } // =================================================================== @@ -28915,7 +27395,7 @@ void Odometry::InternalSwap(Odometry* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Odometry::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[139]); + file_level_metadata_telemetry_2ftelemetry_2eproto[131]); } // =================================================================== @@ -29250,7 +27730,7 @@ void DistanceSensor::InternalSwap(DistanceSensor* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata DistanceSensor::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[140]); + file_level_metadata_telemetry_2ftelemetry_2eproto[132]); } // =================================================================== @@ -29579,7 +28059,7 @@ void ScaledPressure::InternalSwap(ScaledPressure* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata ScaledPressure::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[141]); + file_level_metadata_telemetry_2ftelemetry_2eproto[133]); } // =================================================================== @@ -29848,7 +28328,7 @@ void PositionNed::InternalSwap(PositionNed* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata PositionNed::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[142]); + file_level_metadata_telemetry_2ftelemetry_2eproto[134]); } // =================================================================== @@ -30117,7 +28597,7 @@ void VelocityNed::InternalSwap(VelocityNed* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata VelocityNed::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[143]); + file_level_metadata_telemetry_2ftelemetry_2eproto[135]); } // =================================================================== @@ -30380,7 +28860,7 @@ void PositionVelocityNed::InternalSwap(PositionVelocityNed* PROTOBUF_RESTRICT ot ::google::protobuf::Metadata PositionVelocityNed::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[144]); + file_level_metadata_telemetry_2ftelemetry_2eproto[136]); } // =================================================================== @@ -30649,7 +29129,7 @@ void GroundTruth::InternalSwap(GroundTruth* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata GroundTruth::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[145]); + file_level_metadata_telemetry_2ftelemetry_2eproto[137]); } // =================================================================== @@ -30918,7 +29398,7 @@ void FixedwingMetrics::InternalSwap(FixedwingMetrics* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata FixedwingMetrics::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[146]); + file_level_metadata_telemetry_2ftelemetry_2eproto[138]); } // =================================================================== @@ -31187,7 +29667,7 @@ void AccelerationFrd::InternalSwap(AccelerationFrd* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata AccelerationFrd::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[147]); + file_level_metadata_telemetry_2ftelemetry_2eproto[139]); } // =================================================================== @@ -31456,7 +29936,7 @@ void AngularVelocityFrd::InternalSwap(AngularVelocityFrd* PROTOBUF_RESTRICT othe ::google::protobuf::Metadata AngularVelocityFrd::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[148]); + file_level_metadata_telemetry_2ftelemetry_2eproto[140]); } // =================================================================== @@ -31725,7 +30205,7 @@ void MagneticFieldFrd::InternalSwap(MagneticFieldFrd* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata MagneticFieldFrd::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[149]); + file_level_metadata_telemetry_2ftelemetry_2eproto[141]); } // =================================================================== @@ -32098,7 +30578,7 @@ void Imu::InternalSwap(Imu* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Imu::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[150]); + file_level_metadata_telemetry_2ftelemetry_2eproto[142]); } // =================================================================== @@ -32367,7 +30847,7 @@ void GpsGlobalOrigin::InternalSwap(GpsGlobalOrigin* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata GpsGlobalOrigin::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[151]); + file_level_metadata_telemetry_2ftelemetry_2eproto[143]); } // =================================================================== @@ -32745,7 +31225,7 @@ void Altitude::InternalSwap(Altitude* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata Altitude::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[152]); + file_level_metadata_telemetry_2ftelemetry_2eproto[144]); } // =================================================================== @@ -32961,7 +31441,7 @@ void TelemetryResult::InternalSwap(TelemetryResult* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata TelemetryResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_telemetry_2ftelemetry_2eproto_getter, &descriptor_table_telemetry_2ftelemetry_2eproto_once, - file_level_metadata_telemetry_2ftelemetry_2eproto[153]); + file_level_metadata_telemetry_2ftelemetry_2eproto[145]); } // @@protoc_insertion_point(namespace_scope) } // namespace telemetry diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h index c43dbb26ad..5ec358249c 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h @@ -106,12 +106,6 @@ extern BatteryDefaultTypeInternal _Battery_default_instance_; class BatteryResponse; struct BatteryResponseDefaultTypeInternal; extern BatteryResponseDefaultTypeInternal _BatteryResponse_default_instance_; -class CameraAttitudeEulerResponse; -struct CameraAttitudeEulerResponseDefaultTypeInternal; -extern CameraAttitudeEulerResponseDefaultTypeInternal _CameraAttitudeEulerResponse_default_instance_; -class CameraAttitudeQuaternionResponse; -struct CameraAttitudeQuaternionResponseDefaultTypeInternal; -extern CameraAttitudeQuaternionResponseDefaultTypeInternal _CameraAttitudeQuaternionResponse_default_instance_; class Covariance; struct CovarianceDefaultTypeInternal; extern CovarianceDefaultTypeInternal _Covariance_default_instance_; @@ -280,18 +274,6 @@ extern SetRateBatteryRequestDefaultTypeInternal _SetRateBatteryRequest_default_i class SetRateBatteryResponse; struct SetRateBatteryResponseDefaultTypeInternal; extern SetRateBatteryResponseDefaultTypeInternal _SetRateBatteryResponse_default_instance_; -class SetRateCameraAttitudeQuaternionRequest; -struct SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal; -extern SetRateCameraAttitudeQuaternionRequestDefaultTypeInternal _SetRateCameraAttitudeQuaternionRequest_default_instance_; -class SetRateCameraAttitudeQuaternionResponse; -struct SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal; -extern SetRateCameraAttitudeQuaternionResponseDefaultTypeInternal _SetRateCameraAttitudeQuaternionResponse_default_instance_; -class SetRateCameraAttitudeRequest; -struct SetRateCameraAttitudeRequestDefaultTypeInternal; -extern SetRateCameraAttitudeRequestDefaultTypeInternal _SetRateCameraAttitudeRequest_default_instance_; -class SetRateCameraAttitudeResponse; -struct SetRateCameraAttitudeResponseDefaultTypeInternal; -extern SetRateCameraAttitudeResponseDefaultTypeInternal _SetRateCameraAttitudeResponse_default_instance_; class SetRateDistanceSensorRequest; struct SetRateDistanceSensorRequestDefaultTypeInternal; extern SetRateDistanceSensorRequestDefaultTypeInternal _SetRateDistanceSensorRequest_default_instance_; @@ -427,12 +409,6 @@ extern SubscribeAttitudeQuaternionRequestDefaultTypeInternal _SubscribeAttitudeQ class SubscribeBatteryRequest; struct SubscribeBatteryRequestDefaultTypeInternal; extern SubscribeBatteryRequestDefaultTypeInternal _SubscribeBatteryRequest_default_instance_; -class SubscribeCameraAttitudeEulerRequest; -struct SubscribeCameraAttitudeEulerRequestDefaultTypeInternal; -extern SubscribeCameraAttitudeEulerRequestDefaultTypeInternal _SubscribeCameraAttitudeEulerRequest_default_instance_; -class SubscribeCameraAttitudeQuaternionRequest; -struct SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal; -extern SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal _SubscribeCameraAttitudeQuaternionRequest_default_instance_; class SubscribeDistanceSensorRequest; struct SubscribeDistanceSensorRequestDefaultTypeInternal; extern SubscribeDistanceSensorRequestDefaultTypeInternal _SubscribeDistanceSensorRequest_default_instance_; @@ -1037,7 +1013,7 @@ class VelocityNed final : &_VelocityNed_default_instance_); } static constexpr int kIndexInFileMessages = - 143; + 135; friend void swap(VelocityNed& a, VelocityNed& b) { a.Swap(&b); @@ -1236,7 +1212,7 @@ class VelocityBody final : &_VelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 137; + 129; friend void swap(VelocityBody& a, VelocityBody& b) { a.Swap(&b); @@ -1435,7 +1411,7 @@ class UnixEpochTimeResponse final : &_UnixEpochTimeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 59; + 55; friend void swap(UnixEpochTimeResponse& a, UnixEpochTimeResponse& b) { a.Swap(&b); @@ -1610,7 +1586,7 @@ class TelemetryResult final : &_TelemetryResult_default_instance_); } static constexpr int kIndexInFileMessages = - 153; + 145; friend void swap(TelemetryResult& a, TelemetryResult& b) { a.Swap(&b); @@ -1964,7 +1940,7 @@ class SubscribeVelocityNedRequest final : &_SubscribeVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 18; friend void swap(SubscribeVelocityNedRequest& a, SubscribeVelocityNedRequest& b) { a.Swap(&b); @@ -2100,7 +2076,7 @@ class SubscribeUnixEpochTimeRequest final : &_SubscribeUnixEpochTimeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 58; + 54; friend void swap(SubscribeUnixEpochTimeRequest& a, SubscribeUnixEpochTimeRequest& b) { a.Swap(&b); @@ -2236,7 +2212,7 @@ class SubscribeStatusTextRequest final : &_SubscribeStatusTextRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 36; + 32; friend void swap(SubscribeStatusTextRequest& a, SubscribeStatusTextRequest& b) { a.Swap(&b); @@ -2372,7 +2348,7 @@ class SubscribeScaledPressureRequest final : &_SubscribeScaledPressureRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 62; + 58; friend void swap(SubscribeScaledPressureRequest& a, SubscribeScaledPressureRequest& b) { a.Swap(&b); @@ -2508,7 +2484,7 @@ class SubscribeScaledImuRequest final : &_SubscribeScaledImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 52; + 48; friend void swap(SubscribeScaledImuRequest& a, SubscribeScaledImuRequest& b) { a.Swap(&b); @@ -2644,7 +2620,7 @@ class SubscribeRcStatusRequest final : &_SubscribeRcStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 34; + 30; friend void swap(SubscribeRcStatusRequest& a, SubscribeRcStatusRequest& b) { a.Swap(&b); @@ -2780,7 +2756,7 @@ class SubscribeRawImuRequest final : &_SubscribeRawImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 54; + 50; friend void swap(SubscribeRawImuRequest& a, SubscribeRawImuRequest& b) { a.Swap(&b); @@ -2916,7 +2892,7 @@ class SubscribeRawGpsRequest final : &_SubscribeRawGpsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 22; friend void swap(SubscribeRawGpsRequest& a, SubscribeRawGpsRequest& b) { a.Swap(&b); @@ -3052,7 +3028,7 @@ class SubscribePositionVelocityNedRequest final : &_SubscribePositionVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 44; + 40; friend void swap(SubscribePositionVelocityNedRequest& a, SubscribePositionVelocityNedRequest& b) { a.Swap(&b); @@ -3324,7 +3300,7 @@ class SubscribeOdometryRequest final : &_SubscribeOdometryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 42; + 38; friend void swap(SubscribeOdometryRequest& a, SubscribeOdometryRequest& b) { a.Swap(&b); @@ -3732,7 +3708,7 @@ class SubscribeImuRequest final : &_SubscribeImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 50; + 46; friend void swap(SubscribeImuRequest& a, SubscribeImuRequest& b) { a.Swap(&b); @@ -4004,7 +3980,7 @@ class SubscribeHealthRequest final : &_SubscribeHealthRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 28; friend void swap(SubscribeHealthRequest& a, SubscribeHealthRequest& b) { a.Swap(&b); @@ -4140,7 +4116,7 @@ class SubscribeHealthAllOkRequest final : &_SubscribeHealthAllOkRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 56; + 52; friend void swap(SubscribeHealthAllOkRequest& a, SubscribeHealthAllOkRequest& b) { a.Swap(&b); @@ -4276,7 +4252,7 @@ class SubscribeHeadingRequest final : &_SubscribeHeadingRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 64; + 60; friend void swap(SubscribeHeadingRequest& a, SubscribeHeadingRequest& b) { a.Swap(&b); @@ -4412,7 +4388,7 @@ class SubscribeGroundTruthRequest final : &_SubscribeGroundTruthRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 46; + 42; friend void swap(SubscribeGroundTruthRequest& a, SubscribeGroundTruthRequest& b) { a.Swap(&b); @@ -4548,7 +4524,7 @@ class SubscribeGpsInfoRequest final : &_SubscribeGpsInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 20; friend void swap(SubscribeGpsInfoRequest& a, SubscribeGpsInfoRequest& b) { a.Swap(&b); @@ -4684,7 +4660,7 @@ class SubscribeFlightModeRequest final : &_SubscribeFlightModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 26; friend void swap(SubscribeFlightModeRequest& a, SubscribeFlightModeRequest& b) { a.Swap(&b); @@ -4820,7 +4796,7 @@ class SubscribeFixedwingMetricsRequest final : &_SubscribeFixedwingMetricsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 48; + 44; friend void swap(SubscribeFixedwingMetricsRequest& a, SubscribeFixedwingMetricsRequest& b) { a.Swap(&b); @@ -4956,7 +4932,7 @@ class SubscribeDistanceSensorRequest final : &_SubscribeDistanceSensorRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 60; + 56; friend void swap(SubscribeDistanceSensorRequest& a, SubscribeDistanceSensorRequest& b) { a.Swap(&b); @@ -5034,25 +5010,25 @@ class SubscribeDistanceSensorRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeCameraAttitudeQuaternionRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) */ { +class SubscribeBatteryRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeBatteryRequest) */ { public: - inline SubscribeCameraAttitudeQuaternionRequest() : SubscribeCameraAttitudeQuaternionRequest(nullptr) {} + inline SubscribeBatteryRequest() : SubscribeBatteryRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCameraAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeBatteryRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCameraAttitudeQuaternionRequest(const SubscribeCameraAttitudeQuaternionRequest& from) - : SubscribeCameraAttitudeQuaternionRequest(nullptr, from) {} - SubscribeCameraAttitudeQuaternionRequest(SubscribeCameraAttitudeQuaternionRequest&& from) noexcept - : SubscribeCameraAttitudeQuaternionRequest() { + inline SubscribeBatteryRequest(const SubscribeBatteryRequest& from) + : SubscribeBatteryRequest(nullptr, from) {} + SubscribeBatteryRequest(SubscribeBatteryRequest&& from) noexcept + : SubscribeBatteryRequest() { *this = ::std::move(from); } - inline SubscribeCameraAttitudeQuaternionRequest& operator=(const SubscribeCameraAttitudeQuaternionRequest& from) { + inline SubscribeBatteryRequest& operator=(const SubscribeBatteryRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCameraAttitudeQuaternionRequest& operator=(SubscribeCameraAttitudeQuaternionRequest&& from) noexcept { + inline SubscribeBatteryRequest& operator=(SubscribeBatteryRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5084,20 +5060,20 @@ class SubscribeCameraAttitudeQuaternionRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCameraAttitudeQuaternionRequest& default_instance() { + static const SubscribeBatteryRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCameraAttitudeQuaternionRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCameraAttitudeQuaternionRequest_default_instance_); + static inline const SubscribeBatteryRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeBatteryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 24; - friend void swap(SubscribeCameraAttitudeQuaternionRequest& a, SubscribeCameraAttitudeQuaternionRequest& b) { + friend void swap(SubscribeBatteryRequest& a, SubscribeBatteryRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCameraAttitudeQuaternionRequest* other) { + inline void Swap(SubscribeBatteryRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5110,7 +5086,7 @@ class SubscribeCameraAttitudeQuaternionRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCameraAttitudeQuaternionRequest* other) { + void UnsafeArenaSwap(SubscribeBatteryRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5118,15 +5094,15 @@ class SubscribeCameraAttitudeQuaternionRequest final : // implements Message ---------------------------------------------- - SubscribeCameraAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { + inline void CopyFrom(const SubscribeBatteryRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { + void MergeFrom(const SubscribeBatteryRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5134,11 +5110,11 @@ class SubscribeCameraAttitudeQuaternionRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest"; + return "mavsdk.rpc.telemetry.SubscribeBatteryRequest"; } protected: - explicit SubscribeCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena); - SubscribeCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SubscribeCameraAttitudeQuaternionRequest& from); + explicit SubscribeBatteryRequest(::google::protobuf::Arena* arena); + SubscribeBatteryRequest(::google::protobuf::Arena* arena, const SubscribeBatteryRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5147,7 +5123,7 @@ class SubscribeCameraAttitudeQuaternionRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeBatteryRequest) private: class _Internal; @@ -5170,25 +5146,25 @@ class SubscribeCameraAttitudeQuaternionRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeCameraAttitudeEulerRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) */ { +class SubscribeAttitudeQuaternionRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest) */ { public: - inline SubscribeCameraAttitudeEulerRequest() : SubscribeCameraAttitudeEulerRequest(nullptr) {} + inline SubscribeAttitudeQuaternionRequest() : SubscribeAttitudeQuaternionRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeCameraAttitudeEulerRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeCameraAttitudeEulerRequest(const SubscribeCameraAttitudeEulerRequest& from) - : SubscribeCameraAttitudeEulerRequest(nullptr, from) {} - SubscribeCameraAttitudeEulerRequest(SubscribeCameraAttitudeEulerRequest&& from) noexcept - : SubscribeCameraAttitudeEulerRequest() { + inline SubscribeAttitudeQuaternionRequest(const SubscribeAttitudeQuaternionRequest& from) + : SubscribeAttitudeQuaternionRequest(nullptr, from) {} + SubscribeAttitudeQuaternionRequest(SubscribeAttitudeQuaternionRequest&& from) noexcept + : SubscribeAttitudeQuaternionRequest() { *this = ::std::move(from); } - inline SubscribeCameraAttitudeEulerRequest& operator=(const SubscribeCameraAttitudeEulerRequest& from) { + inline SubscribeAttitudeQuaternionRequest& operator=(const SubscribeAttitudeQuaternionRequest& from) { CopyFrom(from); return *this; } - inline SubscribeCameraAttitudeEulerRequest& operator=(SubscribeCameraAttitudeEulerRequest&& from) noexcept { + inline SubscribeAttitudeQuaternionRequest& operator=(SubscribeAttitudeQuaternionRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5220,20 +5196,20 @@ class SubscribeCameraAttitudeEulerRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeCameraAttitudeEulerRequest& default_instance() { + static const SubscribeAttitudeQuaternionRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeCameraAttitudeEulerRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeCameraAttitudeEulerRequest_default_instance_); + static inline const SubscribeAttitudeQuaternionRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAttitudeQuaternionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 12; - friend void swap(SubscribeCameraAttitudeEulerRequest& a, SubscribeCameraAttitudeEulerRequest& b) { + friend void swap(SubscribeAttitudeQuaternionRequest& a, SubscribeAttitudeQuaternionRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeCameraAttitudeEulerRequest* other) { + inline void Swap(SubscribeAttitudeQuaternionRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5246,7 +5222,7 @@ class SubscribeCameraAttitudeEulerRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeCameraAttitudeEulerRequest* other) { + void UnsafeArenaSwap(SubscribeAttitudeQuaternionRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5254,15 +5230,15 @@ class SubscribeCameraAttitudeEulerRequest final : // implements Message ---------------------------------------------- - SubscribeCameraAttitudeEulerRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeCameraAttitudeEulerRequest& from) { + inline void CopyFrom(const SubscribeAttitudeQuaternionRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeCameraAttitudeEulerRequest& from) { + void MergeFrom(const SubscribeAttitudeQuaternionRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5270,11 +5246,11 @@ class SubscribeCameraAttitudeEulerRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest"; + return "mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest"; } protected: - explicit SubscribeCameraAttitudeEulerRequest(::google::protobuf::Arena* arena); - SubscribeCameraAttitudeEulerRequest(::google::protobuf::Arena* arena, const SubscribeCameraAttitudeEulerRequest& from); + explicit SubscribeAttitudeQuaternionRequest(::google::protobuf::Arena* arena); + SubscribeAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeQuaternionRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5283,7 +5259,7 @@ class SubscribeCameraAttitudeEulerRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest) private: class _Internal; @@ -5306,25 +5282,25 @@ class SubscribeCameraAttitudeEulerRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeBatteryRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeBatteryRequest) */ { +class SubscribeAttitudeEulerRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest) */ { public: - inline SubscribeBatteryRequest() : SubscribeBatteryRequest(nullptr) {} + inline SubscribeAttitudeEulerRequest() : SubscribeAttitudeEulerRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeBatteryRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeAttitudeEulerRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeBatteryRequest(const SubscribeBatteryRequest& from) - : SubscribeBatteryRequest(nullptr, from) {} - SubscribeBatteryRequest(SubscribeBatteryRequest&& from) noexcept - : SubscribeBatteryRequest() { + inline SubscribeAttitudeEulerRequest(const SubscribeAttitudeEulerRequest& from) + : SubscribeAttitudeEulerRequest(nullptr, from) {} + SubscribeAttitudeEulerRequest(SubscribeAttitudeEulerRequest&& from) noexcept + : SubscribeAttitudeEulerRequest() { *this = ::std::move(from); } - inline SubscribeBatteryRequest& operator=(const SubscribeBatteryRequest& from) { + inline SubscribeAttitudeEulerRequest& operator=(const SubscribeAttitudeEulerRequest& from) { CopyFrom(from); return *this; } - inline SubscribeBatteryRequest& operator=(SubscribeBatteryRequest&& from) noexcept { + inline SubscribeAttitudeEulerRequest& operator=(SubscribeAttitudeEulerRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5356,20 +5332,20 @@ class SubscribeBatteryRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeBatteryRequest& default_instance() { + static const SubscribeAttitudeEulerRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeBatteryRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeBatteryRequest_default_instance_); + static inline const SubscribeAttitudeEulerRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAttitudeEulerRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 14; - friend void swap(SubscribeBatteryRequest& a, SubscribeBatteryRequest& b) { + friend void swap(SubscribeAttitudeEulerRequest& a, SubscribeAttitudeEulerRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeBatteryRequest* other) { + inline void Swap(SubscribeAttitudeEulerRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5382,7 +5358,7 @@ class SubscribeBatteryRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeBatteryRequest* other) { + void UnsafeArenaSwap(SubscribeAttitudeEulerRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5390,15 +5366,15 @@ class SubscribeBatteryRequest final : // implements Message ---------------------------------------------- - SubscribeBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeAttitudeEulerRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeBatteryRequest& from) { + inline void CopyFrom(const SubscribeAttitudeEulerRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeBatteryRequest& from) { + void MergeFrom(const SubscribeAttitudeEulerRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5406,11 +5382,11 @@ class SubscribeBatteryRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeBatteryRequest"; + return "mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest"; } protected: - explicit SubscribeBatteryRequest(::google::protobuf::Arena* arena); - SubscribeBatteryRequest(::google::protobuf::Arena* arena, const SubscribeBatteryRequest& from); + explicit SubscribeAttitudeEulerRequest(::google::protobuf::Arena* arena); + SubscribeAttitudeEulerRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeEulerRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5419,7 +5395,7 @@ class SubscribeBatteryRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest) private: class _Internal; @@ -5442,25 +5418,25 @@ class SubscribeBatteryRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeAttitudeQuaternionRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest) */ { +class SubscribeAttitudeAngularVelocityBodyRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) */ { public: - inline SubscribeAttitudeQuaternionRequest() : SubscribeAttitudeQuaternionRequest(nullptr) {} + inline SubscribeAttitudeAngularVelocityBodyRequest() : SubscribeAttitudeAngularVelocityBodyRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeAttitudeQuaternionRequest(const SubscribeAttitudeQuaternionRequest& from) - : SubscribeAttitudeQuaternionRequest(nullptr, from) {} - SubscribeAttitudeQuaternionRequest(SubscribeAttitudeQuaternionRequest&& from) noexcept - : SubscribeAttitudeQuaternionRequest() { + inline SubscribeAttitudeAngularVelocityBodyRequest(const SubscribeAttitudeAngularVelocityBodyRequest& from) + : SubscribeAttitudeAngularVelocityBodyRequest(nullptr, from) {} + SubscribeAttitudeAngularVelocityBodyRequest(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept + : SubscribeAttitudeAngularVelocityBodyRequest() { *this = ::std::move(from); } - inline SubscribeAttitudeQuaternionRequest& operator=(const SubscribeAttitudeQuaternionRequest& from) { + inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(const SubscribeAttitudeAngularVelocityBodyRequest& from) { CopyFrom(from); return *this; } - inline SubscribeAttitudeQuaternionRequest& operator=(SubscribeAttitudeQuaternionRequest&& from) noexcept { + inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5492,20 +5468,20 @@ class SubscribeAttitudeQuaternionRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeAttitudeQuaternionRequest& default_instance() { + static const SubscribeAttitudeAngularVelocityBodyRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeAttitudeQuaternionRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeAttitudeQuaternionRequest_default_instance_); + static inline const SubscribeAttitudeAngularVelocityBodyRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 16; - friend void swap(SubscribeAttitudeQuaternionRequest& a, SubscribeAttitudeQuaternionRequest& b) { + friend void swap(SubscribeAttitudeAngularVelocityBodyRequest& a, SubscribeAttitudeAngularVelocityBodyRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeAttitudeQuaternionRequest* other) { + inline void Swap(SubscribeAttitudeAngularVelocityBodyRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5518,7 +5494,7 @@ class SubscribeAttitudeQuaternionRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeAttitudeQuaternionRequest* other) { + void UnsafeArenaSwap(SubscribeAttitudeAngularVelocityBodyRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5526,15 +5502,15 @@ class SubscribeAttitudeQuaternionRequest final : // implements Message ---------------------------------------------- - SubscribeAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeAttitudeAngularVelocityBodyRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeAttitudeQuaternionRequest& from) { + inline void CopyFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeAttitudeQuaternionRequest& from) { + void MergeFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5542,11 +5518,11 @@ class SubscribeAttitudeQuaternionRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest"; + return "mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest"; } protected: - explicit SubscribeAttitudeQuaternionRequest(::google::protobuf::Arena* arena); - SubscribeAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeQuaternionRequest& from); + explicit SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena); + SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeAngularVelocityBodyRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5555,7 +5531,7 @@ class SubscribeAttitudeQuaternionRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeQuaternionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) private: class _Internal; @@ -5578,25 +5554,25 @@ class SubscribeAttitudeQuaternionRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeAttitudeEulerRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest) */ { +class SubscribeArmedRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeArmedRequest) */ { public: - inline SubscribeAttitudeEulerRequest() : SubscribeAttitudeEulerRequest(nullptr) {} + inline SubscribeArmedRequest() : SubscribeArmedRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeAttitudeEulerRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeArmedRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeAttitudeEulerRequest(const SubscribeAttitudeEulerRequest& from) - : SubscribeAttitudeEulerRequest(nullptr, from) {} - SubscribeAttitudeEulerRequest(SubscribeAttitudeEulerRequest&& from) noexcept - : SubscribeAttitudeEulerRequest() { + inline SubscribeArmedRequest(const SubscribeArmedRequest& from) + : SubscribeArmedRequest(nullptr, from) {} + SubscribeArmedRequest(SubscribeArmedRequest&& from) noexcept + : SubscribeArmedRequest() { *this = ::std::move(from); } - inline SubscribeAttitudeEulerRequest& operator=(const SubscribeAttitudeEulerRequest& from) { + inline SubscribeArmedRequest& operator=(const SubscribeArmedRequest& from) { CopyFrom(from); return *this; } - inline SubscribeAttitudeEulerRequest& operator=(SubscribeAttitudeEulerRequest&& from) noexcept { + inline SubscribeArmedRequest& operator=(SubscribeArmedRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5628,20 +5604,20 @@ class SubscribeAttitudeEulerRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeAttitudeEulerRequest& default_instance() { + static const SubscribeArmedRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeAttitudeEulerRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeAttitudeEulerRequest_default_instance_); + static inline const SubscribeArmedRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeArmedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 8; - friend void swap(SubscribeAttitudeEulerRequest& a, SubscribeAttitudeEulerRequest& b) { + friend void swap(SubscribeArmedRequest& a, SubscribeArmedRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeAttitudeEulerRequest* other) { + inline void Swap(SubscribeArmedRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5654,7 +5630,7 @@ class SubscribeAttitudeEulerRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeAttitudeEulerRequest* other) { + void UnsafeArenaSwap(SubscribeArmedRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5662,15 +5638,15 @@ class SubscribeAttitudeEulerRequest final : // implements Message ---------------------------------------------- - SubscribeAttitudeEulerRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeArmedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeAttitudeEulerRequest& from) { + inline void CopyFrom(const SubscribeArmedRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeAttitudeEulerRequest& from) { + void MergeFrom(const SubscribeArmedRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5678,11 +5654,11 @@ class SubscribeAttitudeEulerRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest"; + return "mavsdk.rpc.telemetry.SubscribeArmedRequest"; } protected: - explicit SubscribeAttitudeEulerRequest(::google::protobuf::Arena* arena); - SubscribeAttitudeEulerRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeEulerRequest& from); + explicit SubscribeArmedRequest(::google::protobuf::Arena* arena); + SubscribeArmedRequest(::google::protobuf::Arena* arena, const SubscribeArmedRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5691,7 +5667,7 @@ class SubscribeAttitudeEulerRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeEulerRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeArmedRequest) private: class _Internal; @@ -5714,25 +5690,25 @@ class SubscribeAttitudeEulerRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeAttitudeAngularVelocityBodyRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) */ { +class SubscribeAltitudeRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) */ { public: - inline SubscribeAttitudeAngularVelocityBodyRequest() : SubscribeAttitudeAngularVelocityBodyRequest(nullptr) {} + inline SubscribeAltitudeRequest() : SubscribeAltitudeRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeAltitudeRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeAttitudeAngularVelocityBodyRequest(const SubscribeAttitudeAngularVelocityBodyRequest& from) - : SubscribeAttitudeAngularVelocityBodyRequest(nullptr, from) {} - SubscribeAttitudeAngularVelocityBodyRequest(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept - : SubscribeAttitudeAngularVelocityBodyRequest() { + inline SubscribeAltitudeRequest(const SubscribeAltitudeRequest& from) + : SubscribeAltitudeRequest(nullptr, from) {} + SubscribeAltitudeRequest(SubscribeAltitudeRequest&& from) noexcept + : SubscribeAltitudeRequest() { *this = ::std::move(from); } - inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(const SubscribeAttitudeAngularVelocityBodyRequest& from) { + inline SubscribeAltitudeRequest& operator=(const SubscribeAltitudeRequest& from) { CopyFrom(from); return *this; } - inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept { + inline SubscribeAltitudeRequest& operator=(SubscribeAltitudeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5764,20 +5740,20 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeAttitudeAngularVelocityBodyRequest& default_instance() { + static const SubscribeAltitudeRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeAttitudeAngularVelocityBodyRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_); + static inline const SubscribeAltitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAltitudeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 62; - friend void swap(SubscribeAttitudeAngularVelocityBodyRequest& a, SubscribeAttitudeAngularVelocityBodyRequest& b) { + friend void swap(SubscribeAltitudeRequest& a, SubscribeAltitudeRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeAttitudeAngularVelocityBodyRequest* other) { + inline void Swap(SubscribeAltitudeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5790,7 +5766,7 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeAttitudeAngularVelocityBodyRequest* other) { + void UnsafeArenaSwap(SubscribeAltitudeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5798,15 +5774,15 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : // implements Message ---------------------------------------------- - SubscribeAttitudeAngularVelocityBodyRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeAltitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { + inline void CopyFrom(const SubscribeAltitudeRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { + void MergeFrom(const SubscribeAltitudeRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5814,11 +5790,11 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest"; + return "mavsdk.rpc.telemetry.SubscribeAltitudeRequest"; } protected: - explicit SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena); - SubscribeAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena, const SubscribeAttitudeAngularVelocityBodyRequest& from); + explicit SubscribeAltitudeRequest(::google::protobuf::Arena* arena); + SubscribeAltitudeRequest(::google::protobuf::Arena* arena, const SubscribeAltitudeRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5827,7 +5803,7 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) private: class _Internal; @@ -5850,25 +5826,25 @@ class SubscribeAttitudeAngularVelocityBodyRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeArmedRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeArmedRequest) */ { +class SubscribeActuatorOutputStatusRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) */ { public: - inline SubscribeArmedRequest() : SubscribeArmedRequest(nullptr) {} + inline SubscribeActuatorOutputStatusRequest() : SubscribeActuatorOutputStatusRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeArmedRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeActuatorOutputStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeArmedRequest(const SubscribeArmedRequest& from) - : SubscribeArmedRequest(nullptr, from) {} - SubscribeArmedRequest(SubscribeArmedRequest&& from) noexcept - : SubscribeArmedRequest() { + inline SubscribeActuatorOutputStatusRequest(const SubscribeActuatorOutputStatusRequest& from) + : SubscribeActuatorOutputStatusRequest(nullptr, from) {} + SubscribeActuatorOutputStatusRequest(SubscribeActuatorOutputStatusRequest&& from) noexcept + : SubscribeActuatorOutputStatusRequest() { *this = ::std::move(from); } - inline SubscribeArmedRequest& operator=(const SubscribeArmedRequest& from) { + inline SubscribeActuatorOutputStatusRequest& operator=(const SubscribeActuatorOutputStatusRequest& from) { CopyFrom(from); return *this; } - inline SubscribeArmedRequest& operator=(SubscribeArmedRequest&& from) noexcept { + inline SubscribeActuatorOutputStatusRequest& operator=(SubscribeActuatorOutputStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -5900,20 +5876,20 @@ class SubscribeArmedRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeArmedRequest& default_instance() { + static const SubscribeActuatorOutputStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeArmedRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeArmedRequest_default_instance_); + static inline const SubscribeActuatorOutputStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeActuatorOutputStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 36; - friend void swap(SubscribeArmedRequest& a, SubscribeArmedRequest& b) { + friend void swap(SubscribeActuatorOutputStatusRequest& a, SubscribeActuatorOutputStatusRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeArmedRequest* other) { + inline void Swap(SubscribeActuatorOutputStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -5926,7 +5902,7 @@ class SubscribeArmedRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeArmedRequest* other) { + void UnsafeArenaSwap(SubscribeActuatorOutputStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -5934,15 +5910,15 @@ class SubscribeArmedRequest final : // implements Message ---------------------------------------------- - SubscribeArmedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeActuatorOutputStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeArmedRequest& from) { + inline void CopyFrom(const SubscribeActuatorOutputStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeArmedRequest& from) { + void MergeFrom(const SubscribeActuatorOutputStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -5950,11 +5926,11 @@ class SubscribeArmedRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeArmedRequest"; + return "mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest"; } protected: - explicit SubscribeArmedRequest(::google::protobuf::Arena* arena); - SubscribeArmedRequest(::google::protobuf::Arena* arena, const SubscribeArmedRequest& from); + explicit SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena); + SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena, const SubscribeActuatorOutputStatusRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -5963,7 +5939,7 @@ class SubscribeArmedRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeArmedRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) private: class _Internal; @@ -5986,25 +5962,25 @@ class SubscribeArmedRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeAltitudeRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) */ { +class SubscribeActuatorControlTargetRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) */ { public: - inline SubscribeAltitudeRequest() : SubscribeAltitudeRequest(nullptr) {} + inline SubscribeActuatorControlTargetRequest() : SubscribeActuatorControlTargetRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeAltitudeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeActuatorControlTargetRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeAltitudeRequest(const SubscribeAltitudeRequest& from) - : SubscribeAltitudeRequest(nullptr, from) {} - SubscribeAltitudeRequest(SubscribeAltitudeRequest&& from) noexcept - : SubscribeAltitudeRequest() { + inline SubscribeActuatorControlTargetRequest(const SubscribeActuatorControlTargetRequest& from) + : SubscribeActuatorControlTargetRequest(nullptr, from) {} + SubscribeActuatorControlTargetRequest(SubscribeActuatorControlTargetRequest&& from) noexcept + : SubscribeActuatorControlTargetRequest() { *this = ::std::move(from); } - inline SubscribeAltitudeRequest& operator=(const SubscribeAltitudeRequest& from) { + inline SubscribeActuatorControlTargetRequest& operator=(const SubscribeActuatorControlTargetRequest& from) { CopyFrom(from); return *this; } - inline SubscribeAltitudeRequest& operator=(SubscribeAltitudeRequest&& from) noexcept { + inline SubscribeActuatorControlTargetRequest& operator=(SubscribeActuatorControlTargetRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6036,20 +6012,20 @@ class SubscribeAltitudeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeAltitudeRequest& default_instance() { + static const SubscribeActuatorControlTargetRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeAltitudeRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeAltitudeRequest_default_instance_); + static inline const SubscribeActuatorControlTargetRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeActuatorControlTargetRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 66; + 34; - friend void swap(SubscribeAltitudeRequest& a, SubscribeAltitudeRequest& b) { + friend void swap(SubscribeActuatorControlTargetRequest& a, SubscribeActuatorControlTargetRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeAltitudeRequest* other) { + inline void Swap(SubscribeActuatorControlTargetRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6062,7 +6038,7 @@ class SubscribeAltitudeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeAltitudeRequest* other) { + void UnsafeArenaSwap(SubscribeActuatorControlTargetRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6070,15 +6046,15 @@ class SubscribeAltitudeRequest final : // implements Message ---------------------------------------------- - SubscribeAltitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeActuatorControlTargetRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeAltitudeRequest& from) { + inline void CopyFrom(const SubscribeActuatorControlTargetRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeAltitudeRequest& from) { + void MergeFrom(const SubscribeActuatorControlTargetRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -6086,11 +6062,11 @@ class SubscribeAltitudeRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeAltitudeRequest"; + return "mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest"; } protected: - explicit SubscribeAltitudeRequest(::google::protobuf::Arena* arena); - SubscribeAltitudeRequest(::google::protobuf::Arena* arena, const SubscribeAltitudeRequest& from); + explicit SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena); + SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena, const SubscribeActuatorControlTargetRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -6099,7 +6075,7 @@ class SubscribeAltitudeRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) private: class _Internal; @@ -6122,25 +6098,26 @@ class SubscribeAltitudeRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeActuatorOutputStatusRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) */ { +class StatusText final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusText) */ { public: - inline SubscribeActuatorOutputStatusRequest() : SubscribeActuatorOutputStatusRequest(nullptr) {} + inline StatusText() : StatusText(nullptr) {} + ~StatusText() override; template - explicit PROTOBUF_CONSTEXPR SubscribeActuatorOutputStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StatusText(::google::protobuf::internal::ConstantInitialized); - inline SubscribeActuatorOutputStatusRequest(const SubscribeActuatorOutputStatusRequest& from) - : SubscribeActuatorOutputStatusRequest(nullptr, from) {} - SubscribeActuatorOutputStatusRequest(SubscribeActuatorOutputStatusRequest&& from) noexcept - : SubscribeActuatorOutputStatusRequest() { + inline StatusText(const StatusText& from) + : StatusText(nullptr, from) {} + StatusText(StatusText&& from) noexcept + : StatusText() { *this = ::std::move(from); } - inline SubscribeActuatorOutputStatusRequest& operator=(const SubscribeActuatorOutputStatusRequest& from) { + inline StatusText& operator=(const StatusText& from) { CopyFrom(from); return *this; } - inline SubscribeActuatorOutputStatusRequest& operator=(SubscribeActuatorOutputStatusRequest&& from) noexcept { + inline StatusText& operator=(StatusText&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6172,20 +6149,20 @@ class SubscribeActuatorOutputStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeActuatorOutputStatusRequest& default_instance() { + static const StatusText& default_instance() { return *internal_default_instance(); } - static inline const SubscribeActuatorOutputStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeActuatorOutputStatusRequest_default_instance_); + static inline const StatusText* internal_default_instance() { + return reinterpret_cast( + &_StatusText_default_instance_); } static constexpr int kIndexInFileMessages = - 40; + 125; - friend void swap(SubscribeActuatorOutputStatusRequest& a, SubscribeActuatorOutputStatusRequest& b) { + friend void swap(StatusText& a, StatusText& b) { a.Swap(&b); } - inline void Swap(SubscribeActuatorOutputStatusRequest* other) { + inline void Swap(StatusText* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6198,7 +6175,7 @@ class SubscribeActuatorOutputStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeActuatorOutputStatusRequest* other) { + void UnsafeArenaSwap(StatusText* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6206,77 +6183,134 @@ class SubscribeActuatorOutputStatusRequest final : // implements Message ---------------------------------------------- - SubscribeActuatorOutputStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeActuatorOutputStatusRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + StatusText* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeActuatorOutputStatusRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const StatusText& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const StatusText& from) { + StatusText::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(StatusText* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest"; + return "mavsdk.rpc.telemetry.StatusText"; } protected: - explicit SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena); - SubscribeActuatorOutputStatusRequest(::google::protobuf::Arena* arena, const SubscribeActuatorOutputStatusRequest& from); + explicit StatusText(::google::protobuf::Arena* arena); + StatusText(::google::protobuf::Arena* arena, const StatusText& 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.telemetry.SubscribeActuatorOutputStatusRequest) - private: - class _Internal; - - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - PROTOBUF_TSAN_DECLARE_MEMBER + enum : int { + kTextFieldNumber = 2, + kTypeFieldNumber = 1, }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; + // string text = 2; + void clear_text() ; + const std::string& text() const; + template + void set_text(Arg_&& arg, Args_... args); + std::string* mutable_text(); + PROTOBUF_NODISCARD std::string* release_text(); + void set_allocated_text(std::string* value); + + private: + const std::string& _internal_text() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_text( + const std::string& value); + std::string* _internal_mutable_text(); + + public: + // .mavsdk.rpc.telemetry.StatusTextType type = 1; + void clear_type() ; + ::mavsdk::rpc::telemetry::StatusTextType type() const; + void set_type(::mavsdk::rpc::telemetry::StatusTextType value); + + private: + ::mavsdk::rpc::telemetry::StatusTextType _internal_type() const; + void _internal_set_type(::mavsdk::rpc::telemetry::StatusTextType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusText) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 0, + 44, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::ArenaStringPtr text_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SubscribeActuatorControlTargetRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) */ { +class SetRateVtolStateRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVtolStateRequest) */ { public: - inline SubscribeActuatorControlTargetRequest() : SubscribeActuatorControlTargetRequest(nullptr) {} + inline SetRateVtolStateRequest() : SetRateVtolStateRequest(nullptr) {} + ~SetRateVtolStateRequest() override; template - explicit PROTOBUF_CONSTEXPR SubscribeActuatorControlTargetRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateVtolStateRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeActuatorControlTargetRequest(const SubscribeActuatorControlTargetRequest& from) - : SubscribeActuatorControlTargetRequest(nullptr, from) {} - SubscribeActuatorControlTargetRequest(SubscribeActuatorControlTargetRequest&& from) noexcept - : SubscribeActuatorControlTargetRequest() { + inline SetRateVtolStateRequest(const SetRateVtolStateRequest& from) + : SetRateVtolStateRequest(nullptr, from) {} + SetRateVtolStateRequest(SetRateVtolStateRequest&& from) noexcept + : SetRateVtolStateRequest() { *this = ::std::move(from); } - inline SubscribeActuatorControlTargetRequest& operator=(const SubscribeActuatorControlTargetRequest& from) { + inline SetRateVtolStateRequest& operator=(const SetRateVtolStateRequest& from) { CopyFrom(from); return *this; } - inline SubscribeActuatorControlTargetRequest& operator=(SubscribeActuatorControlTargetRequest&& from) noexcept { + inline SetRateVtolStateRequest& operator=(SetRateVtolStateRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6308,20 +6342,20 @@ class SubscribeActuatorControlTargetRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeActuatorControlTargetRequest& default_instance() { + static const SetRateVtolStateRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeActuatorControlTargetRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeActuatorControlTargetRequest_default_instance_); + static inline const SetRateVtolStateRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateVtolStateRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 38; + 72; - friend void swap(SubscribeActuatorControlTargetRequest& a, SubscribeActuatorControlTargetRequest& b) { + friend void swap(SetRateVtolStateRequest& a, SetRateVtolStateRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeActuatorControlTargetRequest* other) { + inline void Swap(SetRateVtolStateRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6334,7 +6368,7 @@ class SubscribeActuatorControlTargetRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeActuatorControlTargetRequest* other) { + void UnsafeArenaSwap(SetRateVtolStateRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6342,39 +6376,74 @@ class SubscribeActuatorControlTargetRequest final : // implements Message ---------------------------------------------- - SubscribeActuatorControlTargetRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeActuatorControlTargetRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + SetRateVtolStateRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeActuatorControlTargetRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SetRateVtolStateRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SetRateVtolStateRequest& from) { + SetRateVtolStateRequest::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(SetRateVtolStateRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest"; + return "mavsdk.rpc.telemetry.SetRateVtolStateRequest"; } protected: - explicit SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena); - SubscribeActuatorControlTargetRequest(::google::protobuf::Arena* arena, const SubscribeActuatorControlTargetRequest& from); + explicit SetRateVtolStateRequest(::google::protobuf::Arena* arena); + SetRateVtolStateRequest(::google::protobuf::Arena* arena, const SetRateVtolStateRequest& 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.telemetry.SubscribeActuatorControlTargetRequest) + enum : int { + kRateHzFieldNumber = 1, + }; + // double rate_hz = 1; + void clear_rate_hz() ; + double rate_hz() const; + void set_rate_hz(double value); + + private: + double _internal_rate_hz() const; + void _internal_set_rate_hz(double value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVtolStateRequest) 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 @@ -6389,31 +6458,34 @@ class SubscribeActuatorControlTargetRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + double rate_hz_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class StatusText final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusText) */ { +class SetRateVelocityNedRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVelocityNedRequest) */ { public: - inline StatusText() : StatusText(nullptr) {} - ~StatusText() override; + inline SetRateVelocityNedRequest() : SetRateVelocityNedRequest(nullptr) {} + ~SetRateVelocityNedRequest() override; template - explicit PROTOBUF_CONSTEXPR StatusText(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateVelocityNedRequest(::google::protobuf::internal::ConstantInitialized); - inline StatusText(const StatusText& from) - : StatusText(nullptr, from) {} - StatusText(StatusText&& from) noexcept - : StatusText() { + inline SetRateVelocityNedRequest(const SetRateVelocityNedRequest& from) + : SetRateVelocityNedRequest(nullptr, from) {} + SetRateVelocityNedRequest(SetRateVelocityNedRequest&& from) noexcept + : SetRateVelocityNedRequest() { *this = ::std::move(from); } - inline StatusText& operator=(const StatusText& from) { + inline SetRateVelocityNedRequest& operator=(const SetRateVelocityNedRequest& from) { CopyFrom(from); return *this; } - inline StatusText& operator=(StatusText&& from) noexcept { + inline SetRateVelocityNedRequest& operator=(SetRateVelocityNedRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6445,20 +6517,20 @@ class StatusText final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StatusText& default_instance() { + static const SetRateVelocityNedRequest& default_instance() { return *internal_default_instance(); } - static inline const StatusText* internal_default_instance() { - return reinterpret_cast( - &_StatusText_default_instance_); + static inline const SetRateVelocityNedRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 133; + 80; - friend void swap(StatusText& a, StatusText& b) { + friend void swap(SetRateVelocityNedRequest& a, SetRateVelocityNedRequest& b) { a.Swap(&b); } - inline void Swap(StatusText* other) { + inline void Swap(SetRateVelocityNedRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6471,7 +6543,7 @@ class StatusText final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StatusText* other) { + void UnsafeArenaSwap(SetRateVelocityNedRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6479,14 +6551,14 @@ class StatusText final : // implements Message ---------------------------------------------- - StatusText* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateVelocityNedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StatusText& from); + void CopyFrom(const SetRateVelocityNedRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StatusText& from) { - StatusText::MergeImpl(*this, from); + void MergeFrom( const SetRateVelocityNedRequest& from) { + SetRateVelocityNedRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6504,16 +6576,16 @@ class StatusText final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(StatusText* other); + void InternalSwap(SetRateVelocityNedRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.StatusText"; + return "mavsdk.rpc.telemetry.SetRateVelocityNedRequest"; } protected: - explicit StatusText(::google::protobuf::Arena* arena); - StatusText(::google::protobuf::Arena* arena, const StatusText& from); + explicit SetRateVelocityNedRequest(::google::protobuf::Arena* arena); + SetRateVelocityNedRequest(::google::protobuf::Arena* arena, const SetRateVelocityNedRequest& from); public: static const ClassData _class_data_; @@ -6526,43 +6598,26 @@ class StatusText final : // accessors ------------------------------------------------------- enum : int { - kTextFieldNumber = 2, - kTypeFieldNumber = 1, + kRateHzFieldNumber = 1, }; - // string text = 2; - void clear_text() ; - const std::string& text() const; - template - void set_text(Arg_&& arg, Args_... args); - std::string* mutable_text(); - PROTOBUF_NODISCARD std::string* release_text(); - void set_allocated_text(std::string* value); - - private: - const std::string& _internal_text() const; - inline PROTOBUF_ALWAYS_INLINE void _internal_set_text( - const std::string& value); - std::string* _internal_mutable_text(); - - public: - // .mavsdk.rpc.telemetry.StatusTextType type = 1; - void clear_type() ; - ::mavsdk::rpc::telemetry::StatusTextType type() const; - void set_type(::mavsdk::rpc::telemetry::StatusTextType value); + // double rate_hz = 1; + void clear_rate_hz() ; + double rate_hz() const; + void set_rate_hz(double value); private: - ::mavsdk::rpc::telemetry::StatusTextType _internal_type() const; - void _internal_set_type(::mavsdk::rpc::telemetry::StatusTextType value); + double _internal_rate_hz() const; + void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVelocityNedRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, - 44, 2> + 0, 1, 0, + 0, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -6578,8 +6633,7 @@ class StatusText final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::ArenaStringPtr text_; - int type_; + double rate_hz_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -6587,26 +6641,26 @@ class StatusText final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateVtolStateRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVtolStateRequest) */ { - public: - inline SetRateVtolStateRequest() : SetRateVtolStateRequest(nullptr) {} - ~SetRateVtolStateRequest() override; +class SetRateUnixEpochTimeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest) */ { + public: + inline SetRateUnixEpochTimeRequest() : SetRateUnixEpochTimeRequest(nullptr) {} + ~SetRateUnixEpochTimeRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateVtolStateRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateUnixEpochTimeRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateVtolStateRequest(const SetRateVtolStateRequest& from) - : SetRateVtolStateRequest(nullptr, from) {} - SetRateVtolStateRequest(SetRateVtolStateRequest&& from) noexcept - : SetRateVtolStateRequest() { + inline SetRateUnixEpochTimeRequest(const SetRateUnixEpochTimeRequest& from) + : SetRateUnixEpochTimeRequest(nullptr, from) {} + SetRateUnixEpochTimeRequest(SetRateUnixEpochTimeRequest&& from) noexcept + : SetRateUnixEpochTimeRequest() { *this = ::std::move(from); } - inline SetRateVtolStateRequest& operator=(const SetRateVtolStateRequest& from) { + inline SetRateUnixEpochTimeRequest& operator=(const SetRateUnixEpochTimeRequest& from) { CopyFrom(from); return *this; } - inline SetRateVtolStateRequest& operator=(SetRateVtolStateRequest&& from) noexcept { + inline SetRateUnixEpochTimeRequest& operator=(SetRateUnixEpochTimeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6638,20 +6692,20 @@ class SetRateVtolStateRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateVtolStateRequest& default_instance() { + static const SetRateUnixEpochTimeRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateVtolStateRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateVtolStateRequest_default_instance_); + static inline const SetRateUnixEpochTimeRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateUnixEpochTimeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 76; + 107; - friend void swap(SetRateVtolStateRequest& a, SetRateVtolStateRequest& b) { + friend void swap(SetRateUnixEpochTimeRequest& a, SetRateUnixEpochTimeRequest& b) { a.Swap(&b); } - inline void Swap(SetRateVtolStateRequest* other) { + inline void Swap(SetRateUnixEpochTimeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6664,7 +6718,7 @@ class SetRateVtolStateRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateVtolStateRequest* other) { + void UnsafeArenaSwap(SetRateUnixEpochTimeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6672,14 +6726,14 @@ class SetRateVtolStateRequest final : // implements Message ---------------------------------------------- - SetRateVtolStateRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateUnixEpochTimeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateVtolStateRequest& from); + void CopyFrom(const SetRateUnixEpochTimeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateVtolStateRequest& from) { - SetRateVtolStateRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateUnixEpochTimeRequest& from) { + SetRateUnixEpochTimeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6697,16 +6751,16 @@ class SetRateVtolStateRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateVtolStateRequest* other); + void InternalSwap(SetRateUnixEpochTimeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateVtolStateRequest"; + return "mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest"; } protected: - explicit SetRateVtolStateRequest(::google::protobuf::Arena* arena); - SetRateVtolStateRequest(::google::protobuf::Arena* arena, const SetRateVtolStateRequest& from); + explicit SetRateUnixEpochTimeRequest(::google::protobuf::Arena* arena); + SetRateUnixEpochTimeRequest(::google::protobuf::Arena* arena, const SetRateUnixEpochTimeRequest& from); public: static const ClassData _class_data_; @@ -6731,7 +6785,7 @@ class SetRateVtolStateRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVtolStateRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest) private: class _Internal; @@ -6762,26 +6816,26 @@ class SetRateVtolStateRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateVelocityNedRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVelocityNedRequest) */ { +class SetRateScaledImuRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateScaledImuRequest) */ { public: - inline SetRateVelocityNedRequest() : SetRateVelocityNedRequest(nullptr) {} - ~SetRateVelocityNedRequest() override; + inline SetRateScaledImuRequest() : SetRateScaledImuRequest(nullptr) {} + ~SetRateScaledImuRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateVelocityNedRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateScaledImuRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateVelocityNedRequest(const SetRateVelocityNedRequest& from) - : SetRateVelocityNedRequest(nullptr, from) {} - SetRateVelocityNedRequest(SetRateVelocityNedRequest&& from) noexcept - : SetRateVelocityNedRequest() { + inline SetRateScaledImuRequest(const SetRateScaledImuRequest& from) + : SetRateScaledImuRequest(nullptr, from) {} + SetRateScaledImuRequest(SetRateScaledImuRequest&& from) noexcept + : SetRateScaledImuRequest() { *this = ::std::move(from); } - inline SetRateVelocityNedRequest& operator=(const SetRateVelocityNedRequest& from) { + inline SetRateScaledImuRequest& operator=(const SetRateScaledImuRequest& from) { CopyFrom(from); return *this; } - inline SetRateVelocityNedRequest& operator=(SetRateVelocityNedRequest&& from) noexcept { + inline SetRateScaledImuRequest& operator=(SetRateScaledImuRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6813,20 +6867,20 @@ class SetRateVelocityNedRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateVelocityNedRequest& default_instance() { + static const SetRateScaledImuRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateVelocityNedRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateVelocityNedRequest_default_instance_); + static inline const SetRateScaledImuRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateScaledImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 88; + 103; - friend void swap(SetRateVelocityNedRequest& a, SetRateVelocityNedRequest& b) { + friend void swap(SetRateScaledImuRequest& a, SetRateScaledImuRequest& b) { a.Swap(&b); } - inline void Swap(SetRateVelocityNedRequest* other) { + inline void Swap(SetRateScaledImuRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -6839,7 +6893,7 @@ class SetRateVelocityNedRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateVelocityNedRequest* other) { + void UnsafeArenaSwap(SetRateScaledImuRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6847,14 +6901,14 @@ class SetRateVelocityNedRequest final : // implements Message ---------------------------------------------- - SetRateVelocityNedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateScaledImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateVelocityNedRequest& from); + void CopyFrom(const SetRateScaledImuRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateVelocityNedRequest& from) { - SetRateVelocityNedRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateScaledImuRequest& from) { + SetRateScaledImuRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -6872,16 +6926,16 @@ class SetRateVelocityNedRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateVelocityNedRequest* other); + void InternalSwap(SetRateScaledImuRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateVelocityNedRequest"; + return "mavsdk.rpc.telemetry.SetRateScaledImuRequest"; } protected: - explicit SetRateVelocityNedRequest(::google::protobuf::Arena* arena); - SetRateVelocityNedRequest(::google::protobuf::Arena* arena, const SetRateVelocityNedRequest& from); + explicit SetRateScaledImuRequest(::google::protobuf::Arena* arena); + SetRateScaledImuRequest(::google::protobuf::Arena* arena, const SetRateScaledImuRequest& from); public: static const ClassData _class_data_; @@ -6906,7 +6960,7 @@ class SetRateVelocityNedRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVelocityNedRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateScaledImuRequest) private: class _Internal; @@ -6937,26 +6991,26 @@ class SetRateVelocityNedRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateUnixEpochTimeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest) */ { +class SetRateRcStatusRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRcStatusRequest) */ { public: - inline SetRateUnixEpochTimeRequest() : SetRateUnixEpochTimeRequest(nullptr) {} - ~SetRateUnixEpochTimeRequest() override; + inline SetRateRcStatusRequest() : SetRateRcStatusRequest(nullptr) {} + ~SetRateRcStatusRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateUnixEpochTimeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateRcStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateUnixEpochTimeRequest(const SetRateUnixEpochTimeRequest& from) - : SetRateUnixEpochTimeRequest(nullptr, from) {} - SetRateUnixEpochTimeRequest(SetRateUnixEpochTimeRequest&& from) noexcept - : SetRateUnixEpochTimeRequest() { + inline SetRateRcStatusRequest(const SetRateRcStatusRequest& from) + : SetRateRcStatusRequest(nullptr, from) {} + SetRateRcStatusRequest(SetRateRcStatusRequest&& from) noexcept + : SetRateRcStatusRequest() { *this = ::std::move(from); } - inline SetRateUnixEpochTimeRequest& operator=(const SetRateUnixEpochTimeRequest& from) { + inline SetRateRcStatusRequest& operator=(const SetRateRcStatusRequest& from) { CopyFrom(from); return *this; } - inline SetRateUnixEpochTimeRequest& operator=(SetRateUnixEpochTimeRequest&& from) noexcept { + inline SetRateRcStatusRequest& operator=(SetRateRcStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -6988,20 +7042,20 @@ class SetRateUnixEpochTimeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateUnixEpochTimeRequest& default_instance() { + static const SetRateRcStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateUnixEpochTimeRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateUnixEpochTimeRequest_default_instance_); + static inline const SetRateRcStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateRcStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 115; + 87; - friend void swap(SetRateUnixEpochTimeRequest& a, SetRateUnixEpochTimeRequest& b) { + friend void swap(SetRateRcStatusRequest& a, SetRateRcStatusRequest& b) { a.Swap(&b); } - inline void Swap(SetRateUnixEpochTimeRequest* other) { + inline void Swap(SetRateRcStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7014,7 +7068,7 @@ class SetRateUnixEpochTimeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateUnixEpochTimeRequest* other) { + void UnsafeArenaSwap(SetRateRcStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7022,14 +7076,14 @@ class SetRateUnixEpochTimeRequest final : // implements Message ---------------------------------------------- - SetRateUnixEpochTimeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateRcStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateUnixEpochTimeRequest& from); + void CopyFrom(const SetRateRcStatusRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateUnixEpochTimeRequest& from) { - SetRateUnixEpochTimeRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateRcStatusRequest& from) { + SetRateRcStatusRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7047,16 +7101,16 @@ class SetRateUnixEpochTimeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateUnixEpochTimeRequest* other); + void InternalSwap(SetRateRcStatusRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest"; + return "mavsdk.rpc.telemetry.SetRateRcStatusRequest"; } protected: - explicit SetRateUnixEpochTimeRequest(::google::protobuf::Arena* arena); - SetRateUnixEpochTimeRequest(::google::protobuf::Arena* arena, const SetRateUnixEpochTimeRequest& from); + explicit SetRateRcStatusRequest(::google::protobuf::Arena* arena); + SetRateRcStatusRequest(::google::protobuf::Arena* arena, const SetRateRcStatusRequest& from); public: static const ClassData _class_data_; @@ -7081,7 +7135,7 @@ class SetRateUnixEpochTimeRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateUnixEpochTimeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRcStatusRequest) private: class _Internal; @@ -7112,26 +7166,26 @@ class SetRateUnixEpochTimeRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateScaledImuRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateScaledImuRequest) */ { +class SetRateRawImuRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawImuRequest) */ { public: - inline SetRateScaledImuRequest() : SetRateScaledImuRequest(nullptr) {} - ~SetRateScaledImuRequest() override; + inline SetRateRawImuRequest() : SetRateRawImuRequest(nullptr) {} + ~SetRateRawImuRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateScaledImuRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateRawImuRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateScaledImuRequest(const SetRateScaledImuRequest& from) - : SetRateScaledImuRequest(nullptr, from) {} - SetRateScaledImuRequest(SetRateScaledImuRequest&& from) noexcept - : SetRateScaledImuRequest() { + inline SetRateRawImuRequest(const SetRateRawImuRequest& from) + : SetRateRawImuRequest(nullptr, from) {} + SetRateRawImuRequest(SetRateRawImuRequest&& from) noexcept + : SetRateRawImuRequest() { *this = ::std::move(from); } - inline SetRateScaledImuRequest& operator=(const SetRateScaledImuRequest& from) { + inline SetRateRawImuRequest& operator=(const SetRateRawImuRequest& from) { CopyFrom(from); return *this; } - inline SetRateScaledImuRequest& operator=(SetRateScaledImuRequest&& from) noexcept { + inline SetRateRawImuRequest& operator=(SetRateRawImuRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7163,20 +7217,20 @@ class SetRateScaledImuRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateScaledImuRequest& default_instance() { + static const SetRateRawImuRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateScaledImuRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateScaledImuRequest_default_instance_); + static inline const SetRateRawImuRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateRawImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 111; + 105; - friend void swap(SetRateScaledImuRequest& a, SetRateScaledImuRequest& b) { + friend void swap(SetRateRawImuRequest& a, SetRateRawImuRequest& b) { a.Swap(&b); } - inline void Swap(SetRateScaledImuRequest* other) { + inline void Swap(SetRateRawImuRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7189,7 +7243,7 @@ class SetRateScaledImuRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateScaledImuRequest* other) { + void UnsafeArenaSwap(SetRateRawImuRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7197,14 +7251,14 @@ class SetRateScaledImuRequest final : // implements Message ---------------------------------------------- - SetRateScaledImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateRawImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateScaledImuRequest& from); + void CopyFrom(const SetRateRawImuRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateScaledImuRequest& from) { - SetRateScaledImuRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateRawImuRequest& from) { + SetRateRawImuRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7222,16 +7276,16 @@ class SetRateScaledImuRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateScaledImuRequest* other); + void InternalSwap(SetRateRawImuRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateScaledImuRequest"; + return "mavsdk.rpc.telemetry.SetRateRawImuRequest"; } protected: - explicit SetRateScaledImuRequest(::google::protobuf::Arena* arena); - SetRateScaledImuRequest(::google::protobuf::Arena* arena, const SetRateScaledImuRequest& from); + explicit SetRateRawImuRequest(::google::protobuf::Arena* arena); + SetRateRawImuRequest(::google::protobuf::Arena* arena, const SetRateRawImuRequest& from); public: static const ClassData _class_data_; @@ -7256,7 +7310,7 @@ class SetRateScaledImuRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateScaledImuRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawImuRequest) private: class _Internal; @@ -7287,26 +7341,26 @@ class SetRateScaledImuRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateRcStatusRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRcStatusRequest) */ { +class SetRateRawGpsRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawGpsRequest) */ { public: - inline SetRateRcStatusRequest() : SetRateRcStatusRequest(nullptr) {} - ~SetRateRcStatusRequest() override; + inline SetRateRawGpsRequest() : SetRateRawGpsRequest(nullptr) {} + ~SetRateRawGpsRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateRcStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateRawGpsRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateRcStatusRequest(const SetRateRcStatusRequest& from) - : SetRateRcStatusRequest(nullptr, from) {} - SetRateRcStatusRequest(SetRateRcStatusRequest&& from) noexcept - : SetRateRcStatusRequest() { + inline SetRateRawGpsRequest(const SetRateRawGpsRequest& from) + : SetRateRawGpsRequest(nullptr, from) {} + SetRateRawGpsRequest(SetRateRawGpsRequest&& from) noexcept + : SetRateRawGpsRequest() { *this = ::std::move(from); } - inline SetRateRcStatusRequest& operator=(const SetRateRcStatusRequest& from) { + inline SetRateRawGpsRequest& operator=(const SetRateRawGpsRequest& from) { CopyFrom(from); return *this; } - inline SetRateRcStatusRequest& operator=(SetRateRcStatusRequest&& from) noexcept { + inline SetRateRawGpsRequest& operator=(SetRateRawGpsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7338,20 +7392,20 @@ class SetRateRcStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateRcStatusRequest& default_instance() { + static const SetRateRawGpsRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateRcStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateRcStatusRequest_default_instance_); + static inline const SetRateRawGpsRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateRawGpsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 95; + 84; - friend void swap(SetRateRcStatusRequest& a, SetRateRcStatusRequest& b) { + friend void swap(SetRateRawGpsRequest& a, SetRateRawGpsRequest& b) { a.Swap(&b); } - inline void Swap(SetRateRcStatusRequest* other) { + inline void Swap(SetRateRawGpsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7364,7 +7418,7 @@ class SetRateRcStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateRcStatusRequest* other) { + void UnsafeArenaSwap(SetRateRawGpsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7372,14 +7426,14 @@ class SetRateRcStatusRequest final : // implements Message ---------------------------------------------- - SetRateRcStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateRawGpsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateRcStatusRequest& from); + void CopyFrom(const SetRateRawGpsRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateRcStatusRequest& from) { - SetRateRcStatusRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateRawGpsRequest& from) { + SetRateRawGpsRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7397,16 +7451,16 @@ class SetRateRcStatusRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateRcStatusRequest* other); + void InternalSwap(SetRateRawGpsRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateRcStatusRequest"; + return "mavsdk.rpc.telemetry.SetRateRawGpsRequest"; } protected: - explicit SetRateRcStatusRequest(::google::protobuf::Arena* arena); - SetRateRcStatusRequest(::google::protobuf::Arena* arena, const SetRateRcStatusRequest& from); + explicit SetRateRawGpsRequest(::google::protobuf::Arena* arena); + SetRateRawGpsRequest(::google::protobuf::Arena* arena, const SetRateRawGpsRequest& from); public: static const ClassData _class_data_; @@ -7431,7 +7485,7 @@ class SetRateRcStatusRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRcStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawGpsRequest) private: class _Internal; @@ -7462,26 +7516,26 @@ class SetRateRcStatusRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateRawImuRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawImuRequest) */ { +class SetRatePositionVelocityNedRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest) */ { public: - inline SetRateRawImuRequest() : SetRateRawImuRequest(nullptr) {} - ~SetRateRawImuRequest() override; + inline SetRatePositionVelocityNedRequest() : SetRatePositionVelocityNedRequest(nullptr) {} + ~SetRatePositionVelocityNedRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateRawImuRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRatePositionVelocityNedRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateRawImuRequest(const SetRateRawImuRequest& from) - : SetRateRawImuRequest(nullptr, from) {} - SetRateRawImuRequest(SetRateRawImuRequest&& from) noexcept - : SetRateRawImuRequest() { + inline SetRatePositionVelocityNedRequest(const SetRatePositionVelocityNedRequest& from) + : SetRatePositionVelocityNedRequest(nullptr, from) {} + SetRatePositionVelocityNedRequest(SetRatePositionVelocityNedRequest&& from) noexcept + : SetRatePositionVelocityNedRequest() { *this = ::std::move(from); } - inline SetRateRawImuRequest& operator=(const SetRateRawImuRequest& from) { + inline SetRatePositionVelocityNedRequest& operator=(const SetRatePositionVelocityNedRequest& from) { CopyFrom(from); return *this; } - inline SetRateRawImuRequest& operator=(SetRateRawImuRequest&& from) noexcept { + inline SetRatePositionVelocityNedRequest& operator=(SetRatePositionVelocityNedRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7513,20 +7567,20 @@ class SetRateRawImuRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateRawImuRequest& default_instance() { + static const SetRatePositionVelocityNedRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateRawImuRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateRawImuRequest_default_instance_); + static inline const SetRatePositionVelocityNedRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRatePositionVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 113; + 95; - friend void swap(SetRateRawImuRequest& a, SetRateRawImuRequest& b) { + friend void swap(SetRatePositionVelocityNedRequest& a, SetRatePositionVelocityNedRequest& b) { a.Swap(&b); } - inline void Swap(SetRateRawImuRequest* other) { + inline void Swap(SetRatePositionVelocityNedRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7539,7 +7593,7 @@ class SetRateRawImuRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateRawImuRequest* other) { + void UnsafeArenaSwap(SetRatePositionVelocityNedRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7547,14 +7601,14 @@ class SetRateRawImuRequest final : // implements Message ---------------------------------------------- - SetRateRawImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRatePositionVelocityNedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateRawImuRequest& from); + void CopyFrom(const SetRatePositionVelocityNedRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateRawImuRequest& from) { - SetRateRawImuRequest::MergeImpl(*this, from); + void MergeFrom( const SetRatePositionVelocityNedRequest& from) { + SetRatePositionVelocityNedRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7572,16 +7626,16 @@ class SetRateRawImuRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateRawImuRequest* other); + void InternalSwap(SetRatePositionVelocityNedRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateRawImuRequest"; + return "mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest"; } protected: - explicit SetRateRawImuRequest(::google::protobuf::Arena* arena); - SetRateRawImuRequest(::google::protobuf::Arena* arena, const SetRateRawImuRequest& from); + explicit SetRatePositionVelocityNedRequest(::google::protobuf::Arena* arena); + SetRatePositionVelocityNedRequest(::google::protobuf::Arena* arena, const SetRatePositionVelocityNedRequest& from); public: static const ClassData _class_data_; @@ -7606,7 +7660,7 @@ class SetRateRawImuRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawImuRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest) private: class _Internal; @@ -7637,26 +7691,26 @@ class SetRateRawImuRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateRawGpsRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawGpsRequest) */ { +class SetRatePositionRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionRequest) */ { public: - inline SetRateRawGpsRequest() : SetRateRawGpsRequest(nullptr) {} - ~SetRateRawGpsRequest() override; + inline SetRatePositionRequest() : SetRatePositionRequest(nullptr) {} + ~SetRatePositionRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateRawGpsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRatePositionRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateRawGpsRequest(const SetRateRawGpsRequest& from) - : SetRateRawGpsRequest(nullptr, from) {} - SetRateRawGpsRequest(SetRateRawGpsRequest&& from) noexcept - : SetRateRawGpsRequest() { + inline SetRatePositionRequest(const SetRatePositionRequest& from) + : SetRatePositionRequest(nullptr, from) {} + SetRatePositionRequest(SetRatePositionRequest&& from) noexcept + : SetRatePositionRequest() { *this = ::std::move(from); } - inline SetRateRawGpsRequest& operator=(const SetRateRawGpsRequest& from) { + inline SetRatePositionRequest& operator=(const SetRatePositionRequest& from) { CopyFrom(from); return *this; } - inline SetRateRawGpsRequest& operator=(SetRateRawGpsRequest&& from) noexcept { + inline SetRatePositionRequest& operator=(SetRatePositionRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7688,20 +7742,20 @@ class SetRateRawGpsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateRawGpsRequest& default_instance() { + static const SetRatePositionRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateRawGpsRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateRawGpsRequest_default_instance_); + static inline const SetRatePositionRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRatePositionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 92; + 64; - friend void swap(SetRateRawGpsRequest& a, SetRateRawGpsRequest& b) { + friend void swap(SetRatePositionRequest& a, SetRatePositionRequest& b) { a.Swap(&b); } - inline void Swap(SetRateRawGpsRequest* other) { + inline void Swap(SetRatePositionRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7714,7 +7768,7 @@ class SetRateRawGpsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateRawGpsRequest* other) { + void UnsafeArenaSwap(SetRatePositionRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7722,14 +7776,14 @@ class SetRateRawGpsRequest final : // implements Message ---------------------------------------------- - SetRateRawGpsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRatePositionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateRawGpsRequest& from); + void CopyFrom(const SetRatePositionRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateRawGpsRequest& from) { - SetRateRawGpsRequest::MergeImpl(*this, from); + void MergeFrom( const SetRatePositionRequest& from) { + SetRatePositionRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7747,16 +7801,16 @@ class SetRateRawGpsRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateRawGpsRequest* other); + void InternalSwap(SetRatePositionRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateRawGpsRequest"; + return "mavsdk.rpc.telemetry.SetRatePositionRequest"; } protected: - explicit SetRateRawGpsRequest(::google::protobuf::Arena* arena); - SetRateRawGpsRequest(::google::protobuf::Arena* arena, const SetRateRawGpsRequest& from); + explicit SetRatePositionRequest(::google::protobuf::Arena* arena); + SetRatePositionRequest(::google::protobuf::Arena* arena, const SetRatePositionRequest& from); public: static const ClassData _class_data_; @@ -7781,7 +7835,7 @@ class SetRateRawGpsRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawGpsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionRequest) private: class _Internal; @@ -7812,26 +7866,26 @@ class SetRateRawGpsRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRatePositionVelocityNedRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest) */ { +class SetRateOdometryRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateOdometryRequest) */ { public: - inline SetRatePositionVelocityNedRequest() : SetRatePositionVelocityNedRequest(nullptr) {} - ~SetRatePositionVelocityNedRequest() override; + inline SetRateOdometryRequest() : SetRateOdometryRequest(nullptr) {} + ~SetRateOdometryRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRatePositionVelocityNedRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateOdometryRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRatePositionVelocityNedRequest(const SetRatePositionVelocityNedRequest& from) - : SetRatePositionVelocityNedRequest(nullptr, from) {} - SetRatePositionVelocityNedRequest(SetRatePositionVelocityNedRequest&& from) noexcept - : SetRatePositionVelocityNedRequest() { + inline SetRateOdometryRequest(const SetRateOdometryRequest& from) + : SetRateOdometryRequest(nullptr, from) {} + SetRateOdometryRequest(SetRateOdometryRequest&& from) noexcept + : SetRateOdometryRequest() { *this = ::std::move(from); } - inline SetRatePositionVelocityNedRequest& operator=(const SetRatePositionVelocityNedRequest& from) { + inline SetRateOdometryRequest& operator=(const SetRateOdometryRequest& from) { CopyFrom(from); return *this; } - inline SetRatePositionVelocityNedRequest& operator=(SetRatePositionVelocityNedRequest&& from) noexcept { + inline SetRateOdometryRequest& operator=(SetRateOdometryRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -7863,20 +7917,20 @@ class SetRatePositionVelocityNedRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRatePositionVelocityNedRequest& default_instance() { + static const SetRateOdometryRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRatePositionVelocityNedRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRatePositionVelocityNedRequest_default_instance_); + static inline const SetRateOdometryRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateOdometryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 103; + 93; - friend void swap(SetRatePositionVelocityNedRequest& a, SetRatePositionVelocityNedRequest& b) { + friend void swap(SetRateOdometryRequest& a, SetRateOdometryRequest& b) { a.Swap(&b); } - inline void Swap(SetRatePositionVelocityNedRequest* other) { + inline void Swap(SetRateOdometryRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -7889,7 +7943,7 @@ class SetRatePositionVelocityNedRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRatePositionVelocityNedRequest* other) { + void UnsafeArenaSwap(SetRateOdometryRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7897,14 +7951,14 @@ class SetRatePositionVelocityNedRequest final : // implements Message ---------------------------------------------- - SetRatePositionVelocityNedRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateOdometryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRatePositionVelocityNedRequest& from); + void CopyFrom(const SetRateOdometryRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRatePositionVelocityNedRequest& from) { - SetRatePositionVelocityNedRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateOdometryRequest& from) { + SetRateOdometryRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -7922,16 +7976,16 @@ class SetRatePositionVelocityNedRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRatePositionVelocityNedRequest* other); + void InternalSwap(SetRateOdometryRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest"; + return "mavsdk.rpc.telemetry.SetRateOdometryRequest"; } protected: - explicit SetRatePositionVelocityNedRequest(::google::protobuf::Arena* arena); - SetRatePositionVelocityNedRequest(::google::protobuf::Arena* arena, const SetRatePositionVelocityNedRequest& from); + explicit SetRateOdometryRequest(::google::protobuf::Arena* arena); + SetRateOdometryRequest(::google::protobuf::Arena* arena, const SetRateOdometryRequest& from); public: static const ClassData _class_data_; @@ -7956,7 +8010,7 @@ class SetRatePositionVelocityNedRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionVelocityNedRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateOdometryRequest) private: class _Internal; @@ -7987,26 +8041,26 @@ class SetRatePositionVelocityNedRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRatePositionRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionRequest) */ { +class SetRateLandedStateRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateLandedStateRequest) */ { public: - inline SetRatePositionRequest() : SetRatePositionRequest(nullptr) {} - ~SetRatePositionRequest() override; + inline SetRateLandedStateRequest() : SetRateLandedStateRequest(nullptr) {} + ~SetRateLandedStateRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRatePositionRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateLandedStateRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRatePositionRequest(const SetRatePositionRequest& from) - : SetRatePositionRequest(nullptr, from) {} - SetRatePositionRequest(SetRatePositionRequest&& from) noexcept - : SetRatePositionRequest() { + inline SetRateLandedStateRequest(const SetRateLandedStateRequest& from) + : SetRateLandedStateRequest(nullptr, from) {} + SetRateLandedStateRequest(SetRateLandedStateRequest&& from) noexcept + : SetRateLandedStateRequest() { *this = ::std::move(from); } - inline SetRatePositionRequest& operator=(const SetRatePositionRequest& from) { + inline SetRateLandedStateRequest& operator=(const SetRateLandedStateRequest& from) { CopyFrom(from); return *this; } - inline SetRatePositionRequest& operator=(SetRatePositionRequest&& from) noexcept { + inline SetRateLandedStateRequest& operator=(SetRateLandedStateRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8038,20 +8092,20 @@ class SetRatePositionRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRatePositionRequest& default_instance() { + static const SetRateLandedStateRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRatePositionRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRatePositionRequest_default_instance_); + static inline const SetRateLandedStateRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateLandedStateRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 68; + 70; - friend void swap(SetRatePositionRequest& a, SetRatePositionRequest& b) { + friend void swap(SetRateLandedStateRequest& a, SetRateLandedStateRequest& b) { a.Swap(&b); } - inline void Swap(SetRatePositionRequest* other) { + inline void Swap(SetRateLandedStateRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8064,7 +8118,7 @@ class SetRatePositionRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRatePositionRequest* other) { + void UnsafeArenaSwap(SetRateLandedStateRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8072,14 +8126,14 @@ class SetRatePositionRequest final : // implements Message ---------------------------------------------- - SetRatePositionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateLandedStateRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRatePositionRequest& from); + void CopyFrom(const SetRateLandedStateRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRatePositionRequest& from) { - SetRatePositionRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateLandedStateRequest& from) { + SetRateLandedStateRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8097,16 +8151,16 @@ class SetRatePositionRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRatePositionRequest* other); + void InternalSwap(SetRateLandedStateRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRatePositionRequest"; + return "mavsdk.rpc.telemetry.SetRateLandedStateRequest"; } protected: - explicit SetRatePositionRequest(::google::protobuf::Arena* arena); - SetRatePositionRequest(::google::protobuf::Arena* arena, const SetRatePositionRequest& from); + explicit SetRateLandedStateRequest(::google::protobuf::Arena* arena); + SetRateLandedStateRequest(::google::protobuf::Arena* arena, const SetRateLandedStateRequest& from); public: static const ClassData _class_data_; @@ -8131,7 +8185,7 @@ class SetRatePositionRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateLandedStateRequest) private: class _Internal; @@ -8162,26 +8216,26 @@ class SetRatePositionRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateOdometryRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateOdometryRequest) */ { +class SetRateInAirRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateInAirRequest) */ { public: - inline SetRateOdometryRequest() : SetRateOdometryRequest(nullptr) {} - ~SetRateOdometryRequest() override; + inline SetRateInAirRequest() : SetRateInAirRequest(nullptr) {} + ~SetRateInAirRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateOdometryRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateInAirRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateOdometryRequest(const SetRateOdometryRequest& from) - : SetRateOdometryRequest(nullptr, from) {} - SetRateOdometryRequest(SetRateOdometryRequest&& from) noexcept - : SetRateOdometryRequest() { + inline SetRateInAirRequest(const SetRateInAirRequest& from) + : SetRateInAirRequest(nullptr, from) {} + SetRateInAirRequest(SetRateInAirRequest&& from) noexcept + : SetRateInAirRequest() { *this = ::std::move(from); } - inline SetRateOdometryRequest& operator=(const SetRateOdometryRequest& from) { + inline SetRateInAirRequest& operator=(const SetRateInAirRequest& from) { CopyFrom(from); return *this; } - inline SetRateOdometryRequest& operator=(SetRateOdometryRequest&& from) noexcept { + inline SetRateInAirRequest& operator=(SetRateInAirRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8213,20 +8267,20 @@ class SetRateOdometryRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateOdometryRequest& default_instance() { + static const SetRateInAirRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateOdometryRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateOdometryRequest_default_instance_); + static inline const SetRateInAirRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateInAirRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 101; + 68; - friend void swap(SetRateOdometryRequest& a, SetRateOdometryRequest& b) { + friend void swap(SetRateInAirRequest& a, SetRateInAirRequest& b) { a.Swap(&b); } - inline void Swap(SetRateOdometryRequest* other) { + inline void Swap(SetRateInAirRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8239,7 +8293,7 @@ class SetRateOdometryRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateOdometryRequest* other) { + void UnsafeArenaSwap(SetRateInAirRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8247,14 +8301,14 @@ class SetRateOdometryRequest final : // implements Message ---------------------------------------------- - SetRateOdometryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateInAirRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateOdometryRequest& from); + void CopyFrom(const SetRateInAirRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateOdometryRequest& from) { - SetRateOdometryRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateInAirRequest& from) { + SetRateInAirRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8272,16 +8326,16 @@ class SetRateOdometryRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateOdometryRequest* other); + void InternalSwap(SetRateInAirRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateOdometryRequest"; + return "mavsdk.rpc.telemetry.SetRateInAirRequest"; } protected: - explicit SetRateOdometryRequest(::google::protobuf::Arena* arena); - SetRateOdometryRequest(::google::protobuf::Arena* arena, const SetRateOdometryRequest& from); + explicit SetRateInAirRequest(::google::protobuf::Arena* arena); + SetRateInAirRequest(::google::protobuf::Arena* arena, const SetRateInAirRequest& from); public: static const ClassData _class_data_; @@ -8306,7 +8360,7 @@ class SetRateOdometryRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateOdometryRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateInAirRequest) private: class _Internal; @@ -8337,26 +8391,26 @@ class SetRateOdometryRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateLandedStateRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateLandedStateRequest) */ { +class SetRateImuRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateImuRequest) */ { public: - inline SetRateLandedStateRequest() : SetRateLandedStateRequest(nullptr) {} - ~SetRateLandedStateRequest() override; + inline SetRateImuRequest() : SetRateImuRequest(nullptr) {} + ~SetRateImuRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateLandedStateRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateImuRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateLandedStateRequest(const SetRateLandedStateRequest& from) - : SetRateLandedStateRequest(nullptr, from) {} - SetRateLandedStateRequest(SetRateLandedStateRequest&& from) noexcept - : SetRateLandedStateRequest() { + inline SetRateImuRequest(const SetRateImuRequest& from) + : SetRateImuRequest(nullptr, from) {} + SetRateImuRequest(SetRateImuRequest&& from) noexcept + : SetRateImuRequest() { *this = ::std::move(from); } - inline SetRateLandedStateRequest& operator=(const SetRateLandedStateRequest& from) { + inline SetRateImuRequest& operator=(const SetRateImuRequest& from) { CopyFrom(from); return *this; } - inline SetRateLandedStateRequest& operator=(SetRateLandedStateRequest&& from) noexcept { + inline SetRateImuRequest& operator=(SetRateImuRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8388,20 +8442,20 @@ class SetRateLandedStateRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateLandedStateRequest& default_instance() { + static const SetRateImuRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateLandedStateRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateLandedStateRequest_default_instance_); + static inline const SetRateImuRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 74; + 101; - friend void swap(SetRateLandedStateRequest& a, SetRateLandedStateRequest& b) { + friend void swap(SetRateImuRequest& a, SetRateImuRequest& b) { a.Swap(&b); } - inline void Swap(SetRateLandedStateRequest* other) { + inline void Swap(SetRateImuRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8414,7 +8468,7 @@ class SetRateLandedStateRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateLandedStateRequest* other) { + void UnsafeArenaSwap(SetRateImuRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8422,14 +8476,14 @@ class SetRateLandedStateRequest final : // implements Message ---------------------------------------------- - SetRateLandedStateRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateLandedStateRequest& from); + void CopyFrom(const SetRateImuRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateLandedStateRequest& from) { - SetRateLandedStateRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateImuRequest& from) { + SetRateImuRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8447,16 +8501,16 @@ class SetRateLandedStateRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateLandedStateRequest* other); + void InternalSwap(SetRateImuRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateLandedStateRequest"; + return "mavsdk.rpc.telemetry.SetRateImuRequest"; } protected: - explicit SetRateLandedStateRequest(::google::protobuf::Arena* arena); - SetRateLandedStateRequest(::google::protobuf::Arena* arena, const SetRateLandedStateRequest& from); + explicit SetRateImuRequest(::google::protobuf::Arena* arena); + SetRateImuRequest(::google::protobuf::Arena* arena, const SetRateImuRequest& from); public: static const ClassData _class_data_; @@ -8481,7 +8535,7 @@ class SetRateLandedStateRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateLandedStateRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateImuRequest) private: class _Internal; @@ -8512,26 +8566,26 @@ class SetRateLandedStateRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateInAirRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateInAirRequest) */ { +class SetRateHomeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateHomeRequest) */ { public: - inline SetRateInAirRequest() : SetRateInAirRequest(nullptr) {} - ~SetRateInAirRequest() override; + inline SetRateHomeRequest() : SetRateHomeRequest(nullptr) {} + ~SetRateHomeRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateInAirRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateHomeRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateInAirRequest(const SetRateInAirRequest& from) - : SetRateInAirRequest(nullptr, from) {} - SetRateInAirRequest(SetRateInAirRequest&& from) noexcept - : SetRateInAirRequest() { + inline SetRateHomeRequest(const SetRateHomeRequest& from) + : SetRateHomeRequest(nullptr, from) {} + SetRateHomeRequest(SetRateHomeRequest&& from) noexcept + : SetRateHomeRequest() { *this = ::std::move(from); } - inline SetRateInAirRequest& operator=(const SetRateInAirRequest& from) { + inline SetRateHomeRequest& operator=(const SetRateHomeRequest& from) { CopyFrom(from); return *this; } - inline SetRateInAirRequest& operator=(SetRateInAirRequest&& from) noexcept { + inline SetRateHomeRequest& operator=(SetRateHomeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8563,20 +8617,20 @@ class SetRateInAirRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateInAirRequest& default_instance() { + static const SetRateHomeRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateInAirRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateInAirRequest_default_instance_); + static inline const SetRateHomeRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateHomeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 72; + 66; - friend void swap(SetRateInAirRequest& a, SetRateInAirRequest& b) { + friend void swap(SetRateHomeRequest& a, SetRateHomeRequest& b) { a.Swap(&b); } - inline void Swap(SetRateInAirRequest* other) { + inline void Swap(SetRateHomeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8589,7 +8643,7 @@ class SetRateInAirRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateInAirRequest* other) { + void UnsafeArenaSwap(SetRateHomeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8597,14 +8651,14 @@ class SetRateInAirRequest final : // implements Message ---------------------------------------------- - SetRateInAirRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateHomeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateInAirRequest& from); + void CopyFrom(const SetRateHomeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateInAirRequest& from) { - SetRateInAirRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateHomeRequest& from) { + SetRateHomeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8622,16 +8676,16 @@ class SetRateInAirRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateInAirRequest* other); + void InternalSwap(SetRateHomeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateInAirRequest"; + return "mavsdk.rpc.telemetry.SetRateHomeRequest"; } protected: - explicit SetRateInAirRequest(::google::protobuf::Arena* arena); - SetRateInAirRequest(::google::protobuf::Arena* arena, const SetRateInAirRequest& from); + explicit SetRateHomeRequest(::google::protobuf::Arena* arena); + SetRateHomeRequest(::google::protobuf::Arena* arena, const SetRateHomeRequest& from); public: static const ClassData _class_data_; @@ -8656,7 +8710,7 @@ class SetRateInAirRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateInAirRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateHomeRequest) private: class _Internal; @@ -8687,26 +8741,26 @@ class SetRateInAirRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateImuRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateImuRequest) */ { +class SetRateGroundTruthRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGroundTruthRequest) */ { public: - inline SetRateImuRequest() : SetRateImuRequest(nullptr) {} - ~SetRateImuRequest() override; + inline SetRateGroundTruthRequest() : SetRateGroundTruthRequest(nullptr) {} + ~SetRateGroundTruthRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateImuRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateGroundTruthRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateImuRequest(const SetRateImuRequest& from) - : SetRateImuRequest(nullptr, from) {} - SetRateImuRequest(SetRateImuRequest&& from) noexcept - : SetRateImuRequest() { + inline SetRateGroundTruthRequest(const SetRateGroundTruthRequest& from) + : SetRateGroundTruthRequest(nullptr, from) {} + SetRateGroundTruthRequest(SetRateGroundTruthRequest&& from) noexcept + : SetRateGroundTruthRequest() { *this = ::std::move(from); } - inline SetRateImuRequest& operator=(const SetRateImuRequest& from) { + inline SetRateGroundTruthRequest& operator=(const SetRateGroundTruthRequest& from) { CopyFrom(from); return *this; } - inline SetRateImuRequest& operator=(SetRateImuRequest&& from) noexcept { + inline SetRateGroundTruthRequest& operator=(SetRateGroundTruthRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8738,20 +8792,20 @@ class SetRateImuRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateImuRequest& default_instance() { + static const SetRateGroundTruthRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateImuRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateImuRequest_default_instance_); + static inline const SetRateGroundTruthRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateGroundTruthRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 109; + 97; - friend void swap(SetRateImuRequest& a, SetRateImuRequest& b) { + friend void swap(SetRateGroundTruthRequest& a, SetRateGroundTruthRequest& b) { a.Swap(&b); } - inline void Swap(SetRateImuRequest* other) { + inline void Swap(SetRateGroundTruthRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8764,7 +8818,7 @@ class SetRateImuRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateImuRequest* other) { + void UnsafeArenaSwap(SetRateGroundTruthRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8772,14 +8826,14 @@ class SetRateImuRequest final : // implements Message ---------------------------------------------- - SetRateImuRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateGroundTruthRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateImuRequest& from); + void CopyFrom(const SetRateGroundTruthRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateImuRequest& from) { - SetRateImuRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateGroundTruthRequest& from) { + SetRateGroundTruthRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8797,16 +8851,16 @@ class SetRateImuRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateImuRequest* other); + void InternalSwap(SetRateGroundTruthRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateImuRequest"; + return "mavsdk.rpc.telemetry.SetRateGroundTruthRequest"; } protected: - explicit SetRateImuRequest(::google::protobuf::Arena* arena); - SetRateImuRequest(::google::protobuf::Arena* arena, const SetRateImuRequest& from); + explicit SetRateGroundTruthRequest(::google::protobuf::Arena* arena); + SetRateGroundTruthRequest(::google::protobuf::Arena* arena, const SetRateGroundTruthRequest& from); public: static const ClassData _class_data_; @@ -8831,7 +8885,7 @@ class SetRateImuRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateImuRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGroundTruthRequest) private: class _Internal; @@ -8862,26 +8916,26 @@ class SetRateImuRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateHomeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateHomeRequest) */ { +class SetRateGpsInfoRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGpsInfoRequest) */ { public: - inline SetRateHomeRequest() : SetRateHomeRequest(nullptr) {} - ~SetRateHomeRequest() override; + inline SetRateGpsInfoRequest() : SetRateGpsInfoRequest(nullptr) {} + ~SetRateGpsInfoRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateHomeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateGpsInfoRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateHomeRequest(const SetRateHomeRequest& from) - : SetRateHomeRequest(nullptr, from) {} - SetRateHomeRequest(SetRateHomeRequest&& from) noexcept - : SetRateHomeRequest() { - *this = ::std::move(from); + inline SetRateGpsInfoRequest(const SetRateGpsInfoRequest& from) + : SetRateGpsInfoRequest(nullptr, from) {} + SetRateGpsInfoRequest(SetRateGpsInfoRequest&& from) noexcept + : SetRateGpsInfoRequest() { + *this = ::std::move(from); } - inline SetRateHomeRequest& operator=(const SetRateHomeRequest& from) { + inline SetRateGpsInfoRequest& operator=(const SetRateGpsInfoRequest& from) { CopyFrom(from); return *this; } - inline SetRateHomeRequest& operator=(SetRateHomeRequest&& from) noexcept { + inline SetRateGpsInfoRequest& operator=(SetRateGpsInfoRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -8913,20 +8967,20 @@ class SetRateHomeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateHomeRequest& default_instance() { + static const SetRateGpsInfoRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateHomeRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateHomeRequest_default_instance_); + static inline const SetRateGpsInfoRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateGpsInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 70; + 82; - friend void swap(SetRateHomeRequest& a, SetRateHomeRequest& b) { + friend void swap(SetRateGpsInfoRequest& a, SetRateGpsInfoRequest& b) { a.Swap(&b); } - inline void Swap(SetRateHomeRequest* other) { + inline void Swap(SetRateGpsInfoRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -8939,7 +8993,7 @@ class SetRateHomeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateHomeRequest* other) { + void UnsafeArenaSwap(SetRateGpsInfoRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8947,14 +9001,14 @@ class SetRateHomeRequest final : // implements Message ---------------------------------------------- - SetRateHomeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateGpsInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateHomeRequest& from); + void CopyFrom(const SetRateGpsInfoRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateHomeRequest& from) { - SetRateHomeRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateGpsInfoRequest& from) { + SetRateGpsInfoRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -8972,16 +9026,16 @@ class SetRateHomeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateHomeRequest* other); + void InternalSwap(SetRateGpsInfoRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateHomeRequest"; + return "mavsdk.rpc.telemetry.SetRateGpsInfoRequest"; } protected: - explicit SetRateHomeRequest(::google::protobuf::Arena* arena); - SetRateHomeRequest(::google::protobuf::Arena* arena, const SetRateHomeRequest& from); + explicit SetRateGpsInfoRequest(::google::protobuf::Arena* arena); + SetRateGpsInfoRequest(::google::protobuf::Arena* arena, const SetRateGpsInfoRequest& from); public: static const ClassData _class_data_; @@ -9006,7 +9060,7 @@ class SetRateHomeRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateHomeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGpsInfoRequest) private: class _Internal; @@ -9037,26 +9091,26 @@ class SetRateHomeRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateGroundTruthRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGroundTruthRequest) */ { +class SetRateFixedwingMetricsRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest) */ { public: - inline SetRateGroundTruthRequest() : SetRateGroundTruthRequest(nullptr) {} - ~SetRateGroundTruthRequest() override; + inline SetRateFixedwingMetricsRequest() : SetRateFixedwingMetricsRequest(nullptr) {} + ~SetRateFixedwingMetricsRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateGroundTruthRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateFixedwingMetricsRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateGroundTruthRequest(const SetRateGroundTruthRequest& from) - : SetRateGroundTruthRequest(nullptr, from) {} - SetRateGroundTruthRequest(SetRateGroundTruthRequest&& from) noexcept - : SetRateGroundTruthRequest() { + inline SetRateFixedwingMetricsRequest(const SetRateFixedwingMetricsRequest& from) + : SetRateFixedwingMetricsRequest(nullptr, from) {} + SetRateFixedwingMetricsRequest(SetRateFixedwingMetricsRequest&& from) noexcept + : SetRateFixedwingMetricsRequest() { *this = ::std::move(from); } - inline SetRateGroundTruthRequest& operator=(const SetRateGroundTruthRequest& from) { + inline SetRateFixedwingMetricsRequest& operator=(const SetRateFixedwingMetricsRequest& from) { CopyFrom(from); return *this; } - inline SetRateGroundTruthRequest& operator=(SetRateGroundTruthRequest&& from) noexcept { + inline SetRateFixedwingMetricsRequest& operator=(SetRateFixedwingMetricsRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9088,20 +9142,20 @@ class SetRateGroundTruthRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateGroundTruthRequest& default_instance() { + static const SetRateFixedwingMetricsRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateGroundTruthRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateGroundTruthRequest_default_instance_); + static inline const SetRateFixedwingMetricsRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateFixedwingMetricsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 105; + 99; - friend void swap(SetRateGroundTruthRequest& a, SetRateGroundTruthRequest& b) { + friend void swap(SetRateFixedwingMetricsRequest& a, SetRateFixedwingMetricsRequest& b) { a.Swap(&b); } - inline void Swap(SetRateGroundTruthRequest* other) { + inline void Swap(SetRateFixedwingMetricsRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9114,7 +9168,7 @@ class SetRateGroundTruthRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateGroundTruthRequest* other) { + void UnsafeArenaSwap(SetRateFixedwingMetricsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9122,14 +9176,14 @@ class SetRateGroundTruthRequest final : // implements Message ---------------------------------------------- - SetRateGroundTruthRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateFixedwingMetricsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateGroundTruthRequest& from); + void CopyFrom(const SetRateFixedwingMetricsRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateGroundTruthRequest& from) { - SetRateGroundTruthRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateFixedwingMetricsRequest& from) { + SetRateFixedwingMetricsRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9147,16 +9201,16 @@ class SetRateGroundTruthRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateGroundTruthRequest* other); + void InternalSwap(SetRateFixedwingMetricsRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateGroundTruthRequest"; + return "mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest"; } protected: - explicit SetRateGroundTruthRequest(::google::protobuf::Arena* arena); - SetRateGroundTruthRequest(::google::protobuf::Arena* arena, const SetRateGroundTruthRequest& from); + explicit SetRateFixedwingMetricsRequest(::google::protobuf::Arena* arena); + SetRateFixedwingMetricsRequest(::google::protobuf::Arena* arena, const SetRateFixedwingMetricsRequest& from); public: static const ClassData _class_data_; @@ -9181,7 +9235,7 @@ class SetRateGroundTruthRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGroundTruthRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest) private: class _Internal; @@ -9212,26 +9266,26 @@ class SetRateGroundTruthRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateGpsInfoRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGpsInfoRequest) */ { +class SetRateDistanceSensorRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateDistanceSensorRequest) */ { public: - inline SetRateGpsInfoRequest() : SetRateGpsInfoRequest(nullptr) {} - ~SetRateGpsInfoRequest() override; + inline SetRateDistanceSensorRequest() : SetRateDistanceSensorRequest(nullptr) {} + ~SetRateDistanceSensorRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateGpsInfoRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateDistanceSensorRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateGpsInfoRequest(const SetRateGpsInfoRequest& from) - : SetRateGpsInfoRequest(nullptr, from) {} - SetRateGpsInfoRequest(SetRateGpsInfoRequest&& from) noexcept - : SetRateGpsInfoRequest() { + inline SetRateDistanceSensorRequest(const SetRateDistanceSensorRequest& from) + : SetRateDistanceSensorRequest(nullptr, from) {} + SetRateDistanceSensorRequest(SetRateDistanceSensorRequest&& from) noexcept + : SetRateDistanceSensorRequest() { *this = ::std::move(from); } - inline SetRateGpsInfoRequest& operator=(const SetRateGpsInfoRequest& from) { + inline SetRateDistanceSensorRequest& operator=(const SetRateDistanceSensorRequest& from) { CopyFrom(from); return *this; } - inline SetRateGpsInfoRequest& operator=(SetRateGpsInfoRequest&& from) noexcept { + inline SetRateDistanceSensorRequest& operator=(SetRateDistanceSensorRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9263,20 +9317,20 @@ class SetRateGpsInfoRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateGpsInfoRequest& default_instance() { + static const SetRateDistanceSensorRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateGpsInfoRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateGpsInfoRequest_default_instance_); + static inline const SetRateDistanceSensorRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateDistanceSensorRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 90; + 109; - friend void swap(SetRateGpsInfoRequest& a, SetRateGpsInfoRequest& b) { + friend void swap(SetRateDistanceSensorRequest& a, SetRateDistanceSensorRequest& b) { a.Swap(&b); } - inline void Swap(SetRateGpsInfoRequest* other) { + inline void Swap(SetRateDistanceSensorRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9289,7 +9343,7 @@ class SetRateGpsInfoRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateGpsInfoRequest* other) { + void UnsafeArenaSwap(SetRateDistanceSensorRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9297,14 +9351,14 @@ class SetRateGpsInfoRequest final : // implements Message ---------------------------------------------- - SetRateGpsInfoRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateDistanceSensorRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateGpsInfoRequest& from); + void CopyFrom(const SetRateDistanceSensorRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateGpsInfoRequest& from) { - SetRateGpsInfoRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateDistanceSensorRequest& from) { + SetRateDistanceSensorRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9322,16 +9376,16 @@ class SetRateGpsInfoRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateGpsInfoRequest* other); + void InternalSwap(SetRateDistanceSensorRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateGpsInfoRequest"; + return "mavsdk.rpc.telemetry.SetRateDistanceSensorRequest"; } protected: - explicit SetRateGpsInfoRequest(::google::protobuf::Arena* arena); - SetRateGpsInfoRequest(::google::protobuf::Arena* arena, const SetRateGpsInfoRequest& from); + explicit SetRateDistanceSensorRequest(::google::protobuf::Arena* arena); + SetRateDistanceSensorRequest(::google::protobuf::Arena* arena, const SetRateDistanceSensorRequest& from); public: static const ClassData _class_data_; @@ -9356,7 +9410,7 @@ class SetRateGpsInfoRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGpsInfoRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateDistanceSensorRequest) private: class _Internal; @@ -9387,26 +9441,26 @@ class SetRateGpsInfoRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateFixedwingMetricsRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest) */ { +class SetRateBatteryRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateBatteryRequest) */ { public: - inline SetRateFixedwingMetricsRequest() : SetRateFixedwingMetricsRequest(nullptr) {} - ~SetRateFixedwingMetricsRequest() override; + inline SetRateBatteryRequest() : SetRateBatteryRequest(nullptr) {} + ~SetRateBatteryRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateFixedwingMetricsRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateBatteryRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateFixedwingMetricsRequest(const SetRateFixedwingMetricsRequest& from) - : SetRateFixedwingMetricsRequest(nullptr, from) {} - SetRateFixedwingMetricsRequest(SetRateFixedwingMetricsRequest&& from) noexcept - : SetRateFixedwingMetricsRequest() { + inline SetRateBatteryRequest(const SetRateBatteryRequest& from) + : SetRateBatteryRequest(nullptr, from) {} + SetRateBatteryRequest(SetRateBatteryRequest&& from) noexcept + : SetRateBatteryRequest() { *this = ::std::move(from); } - inline SetRateFixedwingMetricsRequest& operator=(const SetRateFixedwingMetricsRequest& from) { + inline SetRateBatteryRequest& operator=(const SetRateBatteryRequest& from) { CopyFrom(from); return *this; } - inline SetRateFixedwingMetricsRequest& operator=(SetRateFixedwingMetricsRequest&& from) noexcept { + inline SetRateBatteryRequest& operator=(SetRateBatteryRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9438,20 +9492,20 @@ class SetRateFixedwingMetricsRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateFixedwingMetricsRequest& default_instance() { + static const SetRateBatteryRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateFixedwingMetricsRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateFixedwingMetricsRequest_default_instance_); + static inline const SetRateBatteryRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateBatteryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 107; + 85; - friend void swap(SetRateFixedwingMetricsRequest& a, SetRateFixedwingMetricsRequest& b) { + friend void swap(SetRateBatteryRequest& a, SetRateBatteryRequest& b) { a.Swap(&b); } - inline void Swap(SetRateFixedwingMetricsRequest* other) { + inline void Swap(SetRateBatteryRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9464,7 +9518,7 @@ class SetRateFixedwingMetricsRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateFixedwingMetricsRequest* other) { + void UnsafeArenaSwap(SetRateBatteryRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9472,14 +9526,14 @@ class SetRateFixedwingMetricsRequest final : // implements Message ---------------------------------------------- - SetRateFixedwingMetricsRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateFixedwingMetricsRequest& from); + void CopyFrom(const SetRateBatteryRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateFixedwingMetricsRequest& from) { - SetRateFixedwingMetricsRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateBatteryRequest& from) { + SetRateBatteryRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9497,16 +9551,16 @@ class SetRateFixedwingMetricsRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateFixedwingMetricsRequest* other); + void InternalSwap(SetRateBatteryRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest"; + return "mavsdk.rpc.telemetry.SetRateBatteryRequest"; } protected: - explicit SetRateFixedwingMetricsRequest(::google::protobuf::Arena* arena); - SetRateFixedwingMetricsRequest(::google::protobuf::Arena* arena, const SetRateFixedwingMetricsRequest& from); + explicit SetRateBatteryRequest(::google::protobuf::Arena* arena); + SetRateBatteryRequest(::google::protobuf::Arena* arena, const SetRateBatteryRequest& from); public: static const ClassData _class_data_; @@ -9531,7 +9585,7 @@ class SetRateFixedwingMetricsRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateFixedwingMetricsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateBatteryRequest) private: class _Internal; @@ -9562,26 +9616,26 @@ class SetRateFixedwingMetricsRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateDistanceSensorRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateDistanceSensorRequest) */ { +class SetRateAttitudeQuaternionRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) */ { public: - inline SetRateDistanceSensorRequest() : SetRateDistanceSensorRequest(nullptr) {} - ~SetRateDistanceSensorRequest() override; + inline SetRateAttitudeQuaternionRequest() : SetRateAttitudeQuaternionRequest(nullptr) {} + ~SetRateAttitudeQuaternionRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateDistanceSensorRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateDistanceSensorRequest(const SetRateDistanceSensorRequest& from) - : SetRateDistanceSensorRequest(nullptr, from) {} - SetRateDistanceSensorRequest(SetRateDistanceSensorRequest&& from) noexcept - : SetRateDistanceSensorRequest() { + inline SetRateAttitudeQuaternionRequest(const SetRateAttitudeQuaternionRequest& from) + : SetRateAttitudeQuaternionRequest(nullptr, from) {} + SetRateAttitudeQuaternionRequest(SetRateAttitudeQuaternionRequest&& from) noexcept + : SetRateAttitudeQuaternionRequest() { *this = ::std::move(from); } - inline SetRateDistanceSensorRequest& operator=(const SetRateDistanceSensorRequest& from) { + inline SetRateAttitudeQuaternionRequest& operator=(const SetRateAttitudeQuaternionRequest& from) { CopyFrom(from); return *this; } - inline SetRateDistanceSensorRequest& operator=(SetRateDistanceSensorRequest&& from) noexcept { + inline SetRateAttitudeQuaternionRequest& operator=(SetRateAttitudeQuaternionRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9613,20 +9667,20 @@ class SetRateDistanceSensorRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateDistanceSensorRequest& default_instance() { + static const SetRateAttitudeQuaternionRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateDistanceSensorRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateDistanceSensorRequest_default_instance_); + static inline const SetRateAttitudeQuaternionRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeQuaternionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 117; + 76; - friend void swap(SetRateDistanceSensorRequest& a, SetRateDistanceSensorRequest& b) { + friend void swap(SetRateAttitudeQuaternionRequest& a, SetRateAttitudeQuaternionRequest& b) { a.Swap(&b); } - inline void Swap(SetRateDistanceSensorRequest* other) { + inline void Swap(SetRateAttitudeQuaternionRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9639,7 +9693,7 @@ class SetRateDistanceSensorRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateDistanceSensorRequest* other) { + void UnsafeArenaSwap(SetRateAttitudeQuaternionRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9647,14 +9701,14 @@ class SetRateDistanceSensorRequest final : // implements Message ---------------------------------------------- - SetRateDistanceSensorRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateDistanceSensorRequest& from); + void CopyFrom(const SetRateAttitudeQuaternionRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateDistanceSensorRequest& from) { - SetRateDistanceSensorRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeQuaternionRequest& from) { + SetRateAttitudeQuaternionRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9672,16 +9726,16 @@ class SetRateDistanceSensorRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateDistanceSensorRequest* other); + void InternalSwap(SetRateAttitudeQuaternionRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateDistanceSensorRequest"; + return "mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest"; } protected: - explicit SetRateDistanceSensorRequest(::google::protobuf::Arena* arena); - SetRateDistanceSensorRequest(::google::protobuf::Arena* arena, const SetRateDistanceSensorRequest& from); + explicit SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena); + SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionRequest& from); public: static const ClassData _class_data_; @@ -9706,7 +9760,7 @@ class SetRateDistanceSensorRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateDistanceSensorRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) private: class _Internal; @@ -9737,26 +9791,26 @@ class SetRateDistanceSensorRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateCameraAttitudeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) */ { +class SetRateAttitudeEulerRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) */ { public: - inline SetRateCameraAttitudeRequest() : SetRateCameraAttitudeRequest(nullptr) {} - ~SetRateCameraAttitudeRequest() override; + inline SetRateAttitudeEulerRequest() : SetRateAttitudeEulerRequest(nullptr) {} + ~SetRateAttitudeEulerRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateCameraAttitudeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeEulerRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateCameraAttitudeRequest(const SetRateCameraAttitudeRequest& from) - : SetRateCameraAttitudeRequest(nullptr, from) {} - SetRateCameraAttitudeRequest(SetRateCameraAttitudeRequest&& from) noexcept - : SetRateCameraAttitudeRequest() { + inline SetRateAttitudeEulerRequest(const SetRateAttitudeEulerRequest& from) + : SetRateAttitudeEulerRequest(nullptr, from) {} + SetRateAttitudeEulerRequest(SetRateAttitudeEulerRequest&& from) noexcept + : SetRateAttitudeEulerRequest() { *this = ::std::move(from); } - inline SetRateCameraAttitudeRequest& operator=(const SetRateCameraAttitudeRequest& from) { + inline SetRateAttitudeEulerRequest& operator=(const SetRateAttitudeEulerRequest& from) { CopyFrom(from); return *this; } - inline SetRateCameraAttitudeRequest& operator=(SetRateCameraAttitudeRequest&& from) noexcept { + inline SetRateAttitudeEulerRequest& operator=(SetRateAttitudeEulerRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9788,20 +9842,20 @@ class SetRateCameraAttitudeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateCameraAttitudeRequest& default_instance() { + static const SetRateAttitudeEulerRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateCameraAttitudeRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateCameraAttitudeRequest_default_instance_); + static inline const SetRateAttitudeEulerRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeEulerRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 86; + 74; - friend void swap(SetRateCameraAttitudeRequest& a, SetRateCameraAttitudeRequest& b) { + friend void swap(SetRateAttitudeEulerRequest& a, SetRateAttitudeEulerRequest& b) { a.Swap(&b); } - inline void Swap(SetRateCameraAttitudeRequest* other) { + inline void Swap(SetRateAttitudeEulerRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9814,7 +9868,7 @@ class SetRateCameraAttitudeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateCameraAttitudeRequest* other) { + void UnsafeArenaSwap(SetRateAttitudeEulerRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9822,14 +9876,14 @@ class SetRateCameraAttitudeRequest final : // implements Message ---------------------------------------------- - SetRateCameraAttitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeEulerRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateCameraAttitudeRequest& from); + void CopyFrom(const SetRateAttitudeEulerRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateCameraAttitudeRequest& from) { - SetRateCameraAttitudeRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeEulerRequest& from) { + SetRateAttitudeEulerRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -9847,16 +9901,16 @@ class SetRateCameraAttitudeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateCameraAttitudeRequest* other); + void InternalSwap(SetRateAttitudeEulerRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest"; + return "mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest"; } protected: - explicit SetRateCameraAttitudeRequest(::google::protobuf::Arena* arena); - SetRateCameraAttitudeRequest(::google::protobuf::Arena* arena, const SetRateCameraAttitudeRequest& from); + explicit SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena); + SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena, const SetRateAttitudeEulerRequest& from); public: static const ClassData _class_data_; @@ -9881,7 +9935,7 @@ class SetRateCameraAttitudeRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) private: class _Internal; @@ -9912,26 +9966,26 @@ class SetRateCameraAttitudeRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateCameraAttitudeQuaternionRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) */ { +class SetRateAttitudeAngularVelocityBodyRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) */ { public: - inline SetRateCameraAttitudeQuaternionRequest() : SetRateCameraAttitudeQuaternionRequest(nullptr) {} - ~SetRateCameraAttitudeQuaternionRequest() override; + inline SetRateAttitudeAngularVelocityBodyRequest() : SetRateAttitudeAngularVelocityBodyRequest(nullptr) {} + ~SetRateAttitudeAngularVelocityBodyRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateCameraAttitudeQuaternionRequest(const SetRateCameraAttitudeQuaternionRequest& from) - : SetRateCameraAttitudeQuaternionRequest(nullptr, from) {} - SetRateCameraAttitudeQuaternionRequest(SetRateCameraAttitudeQuaternionRequest&& from) noexcept - : SetRateCameraAttitudeQuaternionRequest() { + inline SetRateAttitudeAngularVelocityBodyRequest(const SetRateAttitudeAngularVelocityBodyRequest& from) + : SetRateAttitudeAngularVelocityBodyRequest(nullptr, from) {} + SetRateAttitudeAngularVelocityBodyRequest(SetRateAttitudeAngularVelocityBodyRequest&& from) noexcept + : SetRateAttitudeAngularVelocityBodyRequest() { *this = ::std::move(from); } - inline SetRateCameraAttitudeQuaternionRequest& operator=(const SetRateCameraAttitudeQuaternionRequest& from) { + inline SetRateAttitudeAngularVelocityBodyRequest& operator=(const SetRateAttitudeAngularVelocityBodyRequest& from) { CopyFrom(from); return *this; } - inline SetRateCameraAttitudeQuaternionRequest& operator=(SetRateCameraAttitudeQuaternionRequest&& from) noexcept { + inline SetRateAttitudeAngularVelocityBodyRequest& operator=(SetRateAttitudeAngularVelocityBodyRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -9963,20 +10017,20 @@ class SetRateCameraAttitudeQuaternionRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateCameraAttitudeQuaternionRequest& default_instance() { + static const SetRateAttitudeAngularVelocityBodyRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateCameraAttitudeQuaternionRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateCameraAttitudeQuaternionRequest_default_instance_); + static inline const SetRateAttitudeAngularVelocityBodyRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeAngularVelocityBodyRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 84; + 78; - friend void swap(SetRateCameraAttitudeQuaternionRequest& a, SetRateCameraAttitudeQuaternionRequest& b) { + friend void swap(SetRateAttitudeAngularVelocityBodyRequest& a, SetRateAttitudeAngularVelocityBodyRequest& b) { a.Swap(&b); } - inline void Swap(SetRateCameraAttitudeQuaternionRequest* other) { + inline void Swap(SetRateAttitudeAngularVelocityBodyRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -9989,7 +10043,7 @@ class SetRateCameraAttitudeQuaternionRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateCameraAttitudeQuaternionRequest* other) { + void UnsafeArenaSwap(SetRateAttitudeAngularVelocityBodyRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9997,14 +10051,14 @@ class SetRateCameraAttitudeQuaternionRequest final : // implements Message ---------------------------------------------- - SetRateCameraAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeAngularVelocityBodyRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateCameraAttitudeQuaternionRequest& from); + void CopyFrom(const SetRateAttitudeAngularVelocityBodyRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateCameraAttitudeQuaternionRequest& from) { - SetRateCameraAttitudeQuaternionRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeAngularVelocityBodyRequest& from) { + SetRateAttitudeAngularVelocityBodyRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10022,16 +10076,16 @@ class SetRateCameraAttitudeQuaternionRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateCameraAttitudeQuaternionRequest* other); + void InternalSwap(SetRateAttitudeAngularVelocityBodyRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest"; + return "mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest"; } protected: - explicit SetRateCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena); - SetRateCameraAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SetRateCameraAttitudeQuaternionRequest& from); + explicit SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena); + SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyRequest& from); public: static const ClassData _class_data_; @@ -10056,7 +10110,7 @@ class SetRateCameraAttitudeQuaternionRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) private: class _Internal; @@ -10087,26 +10141,26 @@ class SetRateCameraAttitudeQuaternionRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateBatteryRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateBatteryRequest) */ { +class SetRateAltitudeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeRequest) */ { public: - inline SetRateBatteryRequest() : SetRateBatteryRequest(nullptr) {} - ~SetRateBatteryRequest() override; + inline SetRateAltitudeRequest() : SetRateAltitudeRequest(nullptr) {} + ~SetRateAltitudeRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateBatteryRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAltitudeRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateBatteryRequest(const SetRateBatteryRequest& from) - : SetRateBatteryRequest(nullptr, from) {} - SetRateBatteryRequest(SetRateBatteryRequest&& from) noexcept - : SetRateBatteryRequest() { + inline SetRateAltitudeRequest(const SetRateAltitudeRequest& from) + : SetRateAltitudeRequest(nullptr, from) {} + SetRateAltitudeRequest(SetRateAltitudeRequest&& from) noexcept + : SetRateAltitudeRequest() { *this = ::std::move(from); } - inline SetRateBatteryRequest& operator=(const SetRateBatteryRequest& from) { + inline SetRateAltitudeRequest& operator=(const SetRateAltitudeRequest& from) { CopyFrom(from); return *this; } - inline SetRateBatteryRequest& operator=(SetRateBatteryRequest&& from) noexcept { + inline SetRateAltitudeRequest& operator=(SetRateAltitudeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10138,20 +10192,20 @@ class SetRateBatteryRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateBatteryRequest& default_instance() { + static const SetRateAltitudeRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateBatteryRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateBatteryRequest_default_instance_); + static inline const SetRateAltitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateAltitudeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 93; + 113; - friend void swap(SetRateBatteryRequest& a, SetRateBatteryRequest& b) { + friend void swap(SetRateAltitudeRequest& a, SetRateAltitudeRequest& b) { a.Swap(&b); } - inline void Swap(SetRateBatteryRequest* other) { + inline void Swap(SetRateAltitudeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10164,7 +10218,7 @@ class SetRateBatteryRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateBatteryRequest* other) { + void UnsafeArenaSwap(SetRateAltitudeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10172,14 +10226,14 @@ class SetRateBatteryRequest final : // implements Message ---------------------------------------------- - SetRateBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAltitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateBatteryRequest& from); + void CopyFrom(const SetRateAltitudeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateBatteryRequest& from) { - SetRateBatteryRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateAltitudeRequest& from) { + SetRateAltitudeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10197,16 +10251,16 @@ class SetRateBatteryRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateBatteryRequest* other); + void InternalSwap(SetRateAltitudeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateBatteryRequest"; + return "mavsdk.rpc.telemetry.SetRateAltitudeRequest"; } protected: - explicit SetRateBatteryRequest(::google::protobuf::Arena* arena); - SetRateBatteryRequest(::google::protobuf::Arena* arena, const SetRateBatteryRequest& from); + explicit SetRateAltitudeRequest(::google::protobuf::Arena* arena); + SetRateAltitudeRequest(::google::protobuf::Arena* arena, const SetRateAltitudeRequest& from); public: static const ClassData _class_data_; @@ -10231,7 +10285,7 @@ class SetRateBatteryRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateBatteryRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAltitudeRequest) private: class _Internal; @@ -10262,26 +10316,26 @@ class SetRateBatteryRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeQuaternionRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) */ { +class SetRateActuatorOutputStatusRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest) */ { public: - inline SetRateAttitudeQuaternionRequest() : SetRateAttitudeQuaternionRequest(nullptr) {} - ~SetRateAttitudeQuaternionRequest() override; + inline SetRateActuatorOutputStatusRequest() : SetRateActuatorOutputStatusRequest(nullptr) {} + ~SetRateActuatorOutputStatusRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeQuaternionRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateActuatorOutputStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeQuaternionRequest(const SetRateAttitudeQuaternionRequest& from) - : SetRateAttitudeQuaternionRequest(nullptr, from) {} - SetRateAttitudeQuaternionRequest(SetRateAttitudeQuaternionRequest&& from) noexcept - : SetRateAttitudeQuaternionRequest() { + inline SetRateActuatorOutputStatusRequest(const SetRateActuatorOutputStatusRequest& from) + : SetRateActuatorOutputStatusRequest(nullptr, from) {} + SetRateActuatorOutputStatusRequest(SetRateActuatorOutputStatusRequest&& from) noexcept + : SetRateActuatorOutputStatusRequest() { *this = ::std::move(from); } - inline SetRateAttitudeQuaternionRequest& operator=(const SetRateAttitudeQuaternionRequest& from) { + inline SetRateActuatorOutputStatusRequest& operator=(const SetRateActuatorOutputStatusRequest& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeQuaternionRequest& operator=(SetRateAttitudeQuaternionRequest&& from) noexcept { + inline SetRateActuatorOutputStatusRequest& operator=(SetRateActuatorOutputStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10313,20 +10367,20 @@ class SetRateAttitudeQuaternionRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeQuaternionRequest& default_instance() { + static const SetRateActuatorOutputStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeQuaternionRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeQuaternionRequest_default_instance_); + static inline const SetRateActuatorOutputStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateActuatorOutputStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 80; + 91; - friend void swap(SetRateAttitudeQuaternionRequest& a, SetRateAttitudeQuaternionRequest& b) { + friend void swap(SetRateActuatorOutputStatusRequest& a, SetRateActuatorOutputStatusRequest& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeQuaternionRequest* other) { + inline void Swap(SetRateActuatorOutputStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10339,7 +10393,7 @@ class SetRateAttitudeQuaternionRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeQuaternionRequest* other) { + void UnsafeArenaSwap(SetRateActuatorOutputStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10347,14 +10401,14 @@ class SetRateAttitudeQuaternionRequest final : // implements Message ---------------------------------------------- - SetRateAttitudeQuaternionRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateActuatorOutputStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeQuaternionRequest& from); + void CopyFrom(const SetRateActuatorOutputStatusRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeQuaternionRequest& from) { - SetRateAttitudeQuaternionRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateActuatorOutputStatusRequest& from) { + SetRateActuatorOutputStatusRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10372,16 +10426,16 @@ class SetRateAttitudeQuaternionRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeQuaternionRequest* other); + void InternalSwap(SetRateActuatorOutputStatusRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest"; + return "mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest"; } protected: - explicit SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena); - SetRateAttitudeQuaternionRequest(::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionRequest& from); + explicit SetRateActuatorOutputStatusRequest(::google::protobuf::Arena* arena); + SetRateActuatorOutputStatusRequest(::google::protobuf::Arena* arena, const SetRateActuatorOutputStatusRequest& from); public: static const ClassData _class_data_; @@ -10406,7 +10460,7 @@ class SetRateAttitudeQuaternionRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest) private: class _Internal; @@ -10437,26 +10491,26 @@ class SetRateAttitudeQuaternionRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeEulerRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) */ { +class SetRateActuatorControlTargetRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest) */ { public: - inline SetRateAttitudeEulerRequest() : SetRateAttitudeEulerRequest(nullptr) {} - ~SetRateAttitudeEulerRequest() override; + inline SetRateActuatorControlTargetRequest() : SetRateActuatorControlTargetRequest(nullptr) {} + ~SetRateActuatorControlTargetRequest() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeEulerRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateActuatorControlTargetRequest(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeEulerRequest(const SetRateAttitudeEulerRequest& from) - : SetRateAttitudeEulerRequest(nullptr, from) {} - SetRateAttitudeEulerRequest(SetRateAttitudeEulerRequest&& from) noexcept - : SetRateAttitudeEulerRequest() { + inline SetRateActuatorControlTargetRequest(const SetRateActuatorControlTargetRequest& from) + : SetRateActuatorControlTargetRequest(nullptr, from) {} + SetRateActuatorControlTargetRequest(SetRateActuatorControlTargetRequest&& from) noexcept + : SetRateActuatorControlTargetRequest() { *this = ::std::move(from); } - inline SetRateAttitudeEulerRequest& operator=(const SetRateAttitudeEulerRequest& from) { + inline SetRateActuatorControlTargetRequest& operator=(const SetRateActuatorControlTargetRequest& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeEulerRequest& operator=(SetRateAttitudeEulerRequest&& from) noexcept { + inline SetRateActuatorControlTargetRequest& operator=(SetRateActuatorControlTargetRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10488,20 +10542,20 @@ class SetRateAttitudeEulerRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeEulerRequest& default_instance() { + static const SetRateActuatorControlTargetRequest& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeEulerRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeEulerRequest_default_instance_); + static inline const SetRateActuatorControlTargetRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateActuatorControlTargetRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 78; + 89; - friend void swap(SetRateAttitudeEulerRequest& a, SetRateAttitudeEulerRequest& b) { + friend void swap(SetRateActuatorControlTargetRequest& a, SetRateActuatorControlTargetRequest& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeEulerRequest* other) { + inline void Swap(SetRateActuatorControlTargetRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10514,7 +10568,7 @@ class SetRateAttitudeEulerRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeEulerRequest* other) { + void UnsafeArenaSwap(SetRateActuatorControlTargetRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10522,14 +10576,14 @@ class SetRateAttitudeEulerRequest final : // implements Message ---------------------------------------------- - SetRateAttitudeEulerRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateActuatorControlTargetRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeEulerRequest& from); + void CopyFrom(const SetRateActuatorControlTargetRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeEulerRequest& from) { - SetRateAttitudeEulerRequest::MergeImpl(*this, from); + void MergeFrom( const SetRateActuatorControlTargetRequest& from) { + SetRateActuatorControlTargetRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10547,16 +10601,16 @@ class SetRateAttitudeEulerRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeEulerRequest* other); + void InternalSwap(SetRateActuatorControlTargetRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest"; + return "mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest"; } protected: - explicit SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena); - SetRateAttitudeEulerRequest(::google::protobuf::Arena* arena, const SetRateAttitudeEulerRequest& from); + explicit SetRateActuatorControlTargetRequest(::google::protobuf::Arena* arena); + SetRateActuatorControlTargetRequest(::google::protobuf::Arena* arena, const SetRateActuatorControlTargetRequest& from); public: static const ClassData _class_data_; @@ -10581,7 +10635,7 @@ class SetRateAttitudeEulerRequest final : void _internal_set_rate_hz(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeEulerRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest) private: class _Internal; @@ -10612,26 +10666,26 @@ class SetRateAttitudeEulerRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeAngularVelocityBodyRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) */ { +class ScaledPressure final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ScaledPressure) */ { public: - inline SetRateAttitudeAngularVelocityBodyRequest() : SetRateAttitudeAngularVelocityBodyRequest(nullptr) {} - ~SetRateAttitudeAngularVelocityBodyRequest() override; + inline ScaledPressure() : ScaledPressure(nullptr) {} + ~ScaledPressure() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ScaledPressure(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeAngularVelocityBodyRequest(const SetRateAttitudeAngularVelocityBodyRequest& from) - : SetRateAttitudeAngularVelocityBodyRequest(nullptr, from) {} - SetRateAttitudeAngularVelocityBodyRequest(SetRateAttitudeAngularVelocityBodyRequest&& from) noexcept - : SetRateAttitudeAngularVelocityBodyRequest() { + inline ScaledPressure(const ScaledPressure& from) + : ScaledPressure(nullptr, from) {} + ScaledPressure(ScaledPressure&& from) noexcept + : ScaledPressure() { *this = ::std::move(from); } - inline SetRateAttitudeAngularVelocityBodyRequest& operator=(const SetRateAttitudeAngularVelocityBodyRequest& from) { + inline ScaledPressure& operator=(const ScaledPressure& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeAngularVelocityBodyRequest& operator=(SetRateAttitudeAngularVelocityBodyRequest&& from) noexcept { + inline ScaledPressure& operator=(ScaledPressure&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10663,20 +10717,20 @@ class SetRateAttitudeAngularVelocityBodyRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeAngularVelocityBodyRequest& default_instance() { + static const ScaledPressure& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeAngularVelocityBodyRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeAngularVelocityBodyRequest_default_instance_); + static inline const ScaledPressure* internal_default_instance() { + return reinterpret_cast( + &_ScaledPressure_default_instance_); } static constexpr int kIndexInFileMessages = - 82; + 133; - friend void swap(SetRateAttitudeAngularVelocityBodyRequest& a, SetRateAttitudeAngularVelocityBodyRequest& b) { + friend void swap(ScaledPressure& a, ScaledPressure& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeAngularVelocityBodyRequest* other) { + inline void Swap(ScaledPressure* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10689,7 +10743,7 @@ class SetRateAttitudeAngularVelocityBodyRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeAngularVelocityBodyRequest* other) { + void UnsafeArenaSwap(ScaledPressure* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10697,14 +10751,14 @@ class SetRateAttitudeAngularVelocityBodyRequest final : // implements Message ---------------------------------------------- - SetRateAttitudeAngularVelocityBodyRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ScaledPressure* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeAngularVelocityBodyRequest& from); + void CopyFrom(const ScaledPressure& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeAngularVelocityBodyRequest& from) { - SetRateAttitudeAngularVelocityBodyRequest::MergeImpl(*this, from); + void MergeFrom( const ScaledPressure& from) { + ScaledPressure::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10722,16 +10776,16 @@ class SetRateAttitudeAngularVelocityBodyRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeAngularVelocityBodyRequest* other); + void InternalSwap(ScaledPressure* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest"; + return "mavsdk.rpc.telemetry.ScaledPressure"; } protected: - explicit SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena); - SetRateAttitudeAngularVelocityBodyRequest(::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyRequest& from); + explicit ScaledPressure(::google::protobuf::Arena* arena); + ScaledPressure(::google::protobuf::Arena* arena, const ScaledPressure& from); public: static const ClassData _class_data_; @@ -10744,25 +10798,69 @@ class SetRateAttitudeAngularVelocityBodyRequest final : // accessors ------------------------------------------------------- enum : int { - kRateHzFieldNumber = 1, + kTimestampUsFieldNumber = 1, + kAbsolutePressureHpaFieldNumber = 2, + kDifferentialPressureHpaFieldNumber = 3, + kTemperatureDegFieldNumber = 4, + kDifferentialPressureTemperatureDegFieldNumber = 5, }; - // double rate_hz = 1; - void clear_rate_hz() ; - double rate_hz() const; - void set_rate_hz(double value); + // uint64 timestamp_us = 1; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); private: - double _internal_rate_hz() const; - void _internal_set_rate_hz(double value); + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyRequest) + // float absolute_pressure_hpa = 2; + void clear_absolute_pressure_hpa() ; + float absolute_pressure_hpa() const; + void set_absolute_pressure_hpa(float value); + + private: + float _internal_absolute_pressure_hpa() const; + void _internal_set_absolute_pressure_hpa(float value); + + public: + // float differential_pressure_hpa = 3; + void clear_differential_pressure_hpa() ; + float differential_pressure_hpa() const; + void set_differential_pressure_hpa(float value); + + private: + float _internal_differential_pressure_hpa() const; + void _internal_set_differential_pressure_hpa(float value); + + public: + // float temperature_deg = 4; + void clear_temperature_deg() ; + float temperature_deg() const; + void set_temperature_deg(float value); + + private: + float _internal_temperature_deg() const; + void _internal_set_temperature_deg(float value); + + public: + // float differential_pressure_temperature_deg = 5; + void clear_differential_pressure_temperature_deg() ; + float differential_pressure_temperature_deg() const; + void set_differential_pressure_temperature_deg(float value); + + private: + float _internal_differential_pressure_temperature_deg() const; + void _internal_set_differential_pressure_temperature_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ScaledPressure) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 3, 5, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -10779,7 +10877,11 @@ class SetRateAttitudeAngularVelocityBodyRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double rate_hz_; + ::uint64_t timestamp_us_; + float absolute_pressure_hpa_; + float differential_pressure_hpa_; + float temperature_deg_; + float differential_pressure_temperature_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -10787,26 +10889,26 @@ class SetRateAttitudeAngularVelocityBodyRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAltitudeRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeRequest) */ { +class RcStatus final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatus) */ { public: - inline SetRateAltitudeRequest() : SetRateAltitudeRequest(nullptr) {} - ~SetRateAltitudeRequest() override; + inline RcStatus() : RcStatus(nullptr) {} + ~RcStatus() override; template - explicit PROTOBUF_CONSTEXPR SetRateAltitudeRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RcStatus(::google::protobuf::internal::ConstantInitialized); - inline SetRateAltitudeRequest(const SetRateAltitudeRequest& from) - : SetRateAltitudeRequest(nullptr, from) {} - SetRateAltitudeRequest(SetRateAltitudeRequest&& from) noexcept - : SetRateAltitudeRequest() { + inline RcStatus(const RcStatus& from) + : RcStatus(nullptr, from) {} + RcStatus(RcStatus&& from) noexcept + : RcStatus() { *this = ::std::move(from); } - inline SetRateAltitudeRequest& operator=(const SetRateAltitudeRequest& from) { + inline RcStatus& operator=(const RcStatus& from) { CopyFrom(from); return *this; } - inline SetRateAltitudeRequest& operator=(SetRateAltitudeRequest&& from) noexcept { + inline RcStatus& operator=(RcStatus&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -10838,20 +10940,20 @@ class SetRateAltitudeRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAltitudeRequest& default_instance() { + static const RcStatus& default_instance() { return *internal_default_instance(); } - static inline const SetRateAltitudeRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateAltitudeRequest_default_instance_); + static inline const RcStatus* internal_default_instance() { + return reinterpret_cast( + &_RcStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 121; + 124; - friend void swap(SetRateAltitudeRequest& a, SetRateAltitudeRequest& b) { + friend void swap(RcStatus& a, RcStatus& b) { a.Swap(&b); } - inline void Swap(SetRateAltitudeRequest* other) { + inline void Swap(RcStatus* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -10864,7 +10966,7 @@ class SetRateAltitudeRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAltitudeRequest* other) { + void UnsafeArenaSwap(RcStatus* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10872,14 +10974,14 @@ class SetRateAltitudeRequest final : // implements Message ---------------------------------------------- - SetRateAltitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RcStatus* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAltitudeRequest& from); + void CopyFrom(const RcStatus& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAltitudeRequest& from) { - SetRateAltitudeRequest::MergeImpl(*this, from); + void MergeFrom( const RcStatus& from) { + RcStatus::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -10897,16 +10999,16 @@ class SetRateAltitudeRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAltitudeRequest* other); + void InternalSwap(RcStatus* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAltitudeRequest"; + return "mavsdk.rpc.telemetry.RcStatus"; } protected: - explicit SetRateAltitudeRequest(::google::protobuf::Arena* arena); - SetRateAltitudeRequest(::google::protobuf::Arena* arena, const SetRateAltitudeRequest& from); + explicit RcStatus(::google::protobuf::Arena* arena); + RcStatus(::google::protobuf::Arena* arena, const RcStatus& from); public: static const ClassData _class_data_; @@ -10919,25 +11021,47 @@ class SetRateAltitudeRequest final : // accessors ------------------------------------------------------- enum : int { - kRateHzFieldNumber = 1, + kWasAvailableOnceFieldNumber = 1, + kIsAvailableFieldNumber = 2, + kSignalStrengthPercentFieldNumber = 3, }; - // double rate_hz = 1; - void clear_rate_hz() ; - double rate_hz() const; - void set_rate_hz(double value); + // bool was_available_once = 1 [(.mavsdk.options.default_value) = "false"]; + void clear_was_available_once() ; + bool was_available_once() const; + void set_was_available_once(bool value); private: - double _internal_rate_hz() const; - void _internal_set_rate_hz(double value); + bool _internal_was_available_once() const; + void _internal_set_was_available_once(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + // bool is_available = 2 [(.mavsdk.options.default_value) = "false"]; + void clear_is_available() ; + bool is_available() const; + void set_is_available(bool value); + + private: + bool _internal_is_available() const; + void _internal_set_is_available(bool value); + + public: + // float signal_strength_percent = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_signal_strength_percent() ; + float signal_strength_percent() const; + void set_signal_strength_percent(float value); + + private: + float _internal_signal_strength_percent() const; + void _internal_set_signal_strength_percent(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatus) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -10954,7 +11078,9 @@ class SetRateAltitudeRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double rate_hz_; + bool was_available_once_; + bool is_available_; + float signal_strength_percent_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -10962,26 +11088,26 @@ class SetRateAltitudeRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateActuatorOutputStatusRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest) */ { +class RawGps final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RawGps) */ { public: - inline SetRateActuatorOutputStatusRequest() : SetRateActuatorOutputStatusRequest(nullptr) {} - ~SetRateActuatorOutputStatusRequest() override; + inline RawGps() : RawGps(nullptr) {} + ~RawGps() override; template - explicit PROTOBUF_CONSTEXPR SetRateActuatorOutputStatusRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RawGps(::google::protobuf::internal::ConstantInitialized); - inline SetRateActuatorOutputStatusRequest(const SetRateActuatorOutputStatusRequest& from) - : SetRateActuatorOutputStatusRequest(nullptr, from) {} - SetRateActuatorOutputStatusRequest(SetRateActuatorOutputStatusRequest&& from) noexcept - : SetRateActuatorOutputStatusRequest() { + inline RawGps(const RawGps& from) + : RawGps(nullptr, from) {} + RawGps(RawGps&& from) noexcept + : RawGps() { *this = ::std::move(from); } - inline SetRateActuatorOutputStatusRequest& operator=(const SetRateActuatorOutputStatusRequest& from) { + inline RawGps& operator=(const RawGps& from) { CopyFrom(from); return *this; } - inline SetRateActuatorOutputStatusRequest& operator=(SetRateActuatorOutputStatusRequest&& from) noexcept { + inline RawGps& operator=(RawGps&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -11013,20 +11139,20 @@ class SetRateActuatorOutputStatusRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateActuatorOutputStatusRequest& default_instance() { + static const RawGps& default_instance() { return *internal_default_instance(); } - static inline const SetRateActuatorOutputStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateActuatorOutputStatusRequest_default_instance_); + static inline const RawGps* internal_default_instance() { + return reinterpret_cast( + &_RawGps_default_instance_); } static constexpr int kIndexInFileMessages = - 99; + 121; - friend void swap(SetRateActuatorOutputStatusRequest& a, SetRateActuatorOutputStatusRequest& b) { + friend void swap(RawGps& a, RawGps& b) { a.Swap(&b); } - inline void Swap(SetRateActuatorOutputStatusRequest* other) { + inline void Swap(RawGps* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -11039,7 +11165,7 @@ class SetRateActuatorOutputStatusRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateActuatorOutputStatusRequest* other) { + void UnsafeArenaSwap(RawGps* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11047,14 +11173,14 @@ class SetRateActuatorOutputStatusRequest final : // implements Message ---------------------------------------------- - SetRateActuatorOutputStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RawGps* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateActuatorOutputStatusRequest& from); + void CopyFrom(const RawGps& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateActuatorOutputStatusRequest& from) { - SetRateActuatorOutputStatusRequest::MergeImpl(*this, from); + void MergeFrom( const RawGps& from) { + RawGps::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -11072,16 +11198,16 @@ class SetRateActuatorOutputStatusRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateActuatorOutputStatusRequest* other); + void InternalSwap(RawGps* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest"; + return "mavsdk.rpc.telemetry.RawGps"; } protected: - explicit SetRateActuatorOutputStatusRequest(::google::protobuf::Arena* arena); - SetRateActuatorOutputStatusRequest(::google::protobuf::Arena* arena, const SetRateActuatorOutputStatusRequest& from); + explicit RawGps(::google::protobuf::Arena* arena); + RawGps(::google::protobuf::Arena* arena, const RawGps& from); public: static const ClassData _class_data_; @@ -11094,25 +11220,168 @@ class SetRateActuatorOutputStatusRequest final : // accessors ------------------------------------------------------- enum : int { - kRateHzFieldNumber = 1, + kTimestampUsFieldNumber = 1, + kLatitudeDegFieldNumber = 2, + kLongitudeDegFieldNumber = 3, + kAbsoluteAltitudeMFieldNumber = 4, + kHdopFieldNumber = 5, + kVdopFieldNumber = 6, + kVelocityMSFieldNumber = 7, + kCogDegFieldNumber = 8, + kAltitudeEllipsoidMFieldNumber = 9, + kHorizontalUncertaintyMFieldNumber = 10, + kVerticalUncertaintyMFieldNumber = 11, + kVelocityUncertaintyMSFieldNumber = 12, + kHeadingUncertaintyDegFieldNumber = 13, + kYawDegFieldNumber = 14, }; - // double rate_hz = 1; - void clear_rate_hz() ; - double rate_hz() const; - void set_rate_hz(double value); + // uint64 timestamp_us = 1; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); private: - double _internal_rate_hz() const; - void _internal_set_rate_hz(double value); + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusRequest) + // double latitude_deg = 2; + 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 = 3; + 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 = 4; + 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 hdop = 5; + void clear_hdop() ; + float hdop() const; + void set_hdop(float value); + + private: + float _internal_hdop() const; + void _internal_set_hdop(float value); + + public: + // float vdop = 6; + void clear_vdop() ; + float vdop() const; + void set_vdop(float value); + + private: + float _internal_vdop() const; + void _internal_set_vdop(float value); + + public: + // float velocity_m_s = 7; + void clear_velocity_m_s() ; + float velocity_m_s() const; + void set_velocity_m_s(float value); + + private: + float _internal_velocity_m_s() const; + void _internal_set_velocity_m_s(float value); + + public: + // float cog_deg = 8; + void clear_cog_deg() ; + float cog_deg() const; + void set_cog_deg(float value); + + private: + float _internal_cog_deg() const; + void _internal_set_cog_deg(float value); + + public: + // float altitude_ellipsoid_m = 9; + void clear_altitude_ellipsoid_m() ; + float altitude_ellipsoid_m() const; + void set_altitude_ellipsoid_m(float value); + + private: + float _internal_altitude_ellipsoid_m() const; + void _internal_set_altitude_ellipsoid_m(float value); + + public: + // float horizontal_uncertainty_m = 10; + void clear_horizontal_uncertainty_m() ; + float horizontal_uncertainty_m() const; + void set_horizontal_uncertainty_m(float value); + + private: + float _internal_horizontal_uncertainty_m() const; + void _internal_set_horizontal_uncertainty_m(float value); + + public: + // float vertical_uncertainty_m = 11; + void clear_vertical_uncertainty_m() ; + float vertical_uncertainty_m() const; + void set_vertical_uncertainty_m(float value); + + private: + float _internal_vertical_uncertainty_m() const; + void _internal_set_vertical_uncertainty_m(float value); + + public: + // float velocity_uncertainty_m_s = 12; + void clear_velocity_uncertainty_m_s() ; + float velocity_uncertainty_m_s() const; + void set_velocity_uncertainty_m_s(float value); + + private: + float _internal_velocity_uncertainty_m_s() const; + void _internal_set_velocity_uncertainty_m_s(float value); + + public: + // float heading_uncertainty_deg = 13; + void clear_heading_uncertainty_deg() ; + float heading_uncertainty_deg() const; + void set_heading_uncertainty_deg(float value); + + private: + float _internal_heading_uncertainty_deg() const; + void _internal_set_heading_uncertainty_deg(float value); + + public: + // float yaw_deg = 14; + void clear_yaw_deg() ; + float yaw_deg() const; + void set_yaw_deg(float value); + + private: + float _internal_yaw_deg() const; + void _internal_set_yaw_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RawGps) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 4, 14, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -11129,7 +11398,20 @@ class SetRateActuatorOutputStatusRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double rate_hz_; + ::uint64_t timestamp_us_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float hdop_; + float vdop_; + float velocity_m_s_; + float cog_deg_; + float altitude_ellipsoid_m_; + float horizontal_uncertainty_m_; + float vertical_uncertainty_m_; + float velocity_uncertainty_m_s_; + float heading_uncertainty_deg_; + float yaw_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -11137,26 +11419,26 @@ class SetRateActuatorOutputStatusRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateActuatorControlTargetRequest final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest) */ { +class Quaternion final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Quaternion) */ { public: - inline SetRateActuatorControlTargetRequest() : SetRateActuatorControlTargetRequest(nullptr) {} - ~SetRateActuatorControlTargetRequest() override; + inline Quaternion() : Quaternion(nullptr) {} + ~Quaternion() override; template - explicit PROTOBUF_CONSTEXPR SetRateActuatorControlTargetRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); - inline SetRateActuatorControlTargetRequest(const SetRateActuatorControlTargetRequest& from) - : SetRateActuatorControlTargetRequest(nullptr, from) {} - SetRateActuatorControlTargetRequest(SetRateActuatorControlTargetRequest&& from) noexcept - : SetRateActuatorControlTargetRequest() { + inline Quaternion(const Quaternion& from) + : Quaternion(nullptr, from) {} + Quaternion(Quaternion&& from) noexcept + : Quaternion() { *this = ::std::move(from); } - inline SetRateActuatorControlTargetRequest& operator=(const SetRateActuatorControlTargetRequest& from) { + inline Quaternion& operator=(const Quaternion& from) { CopyFrom(from); return *this; } - inline SetRateActuatorControlTargetRequest& operator=(SetRateActuatorControlTargetRequest&& from) noexcept { + inline Quaternion& operator=(Quaternion&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -11188,20 +11470,20 @@ class SetRateActuatorControlTargetRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateActuatorControlTargetRequest& default_instance() { + static const Quaternion& default_instance() { return *internal_default_instance(); } - static inline const SetRateActuatorControlTargetRequest* internal_default_instance() { - return reinterpret_cast( - &_SetRateActuatorControlTargetRequest_default_instance_); + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 97; + 117; - friend void swap(SetRateActuatorControlTargetRequest& a, SetRateActuatorControlTargetRequest& b) { + friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); } - inline void Swap(SetRateActuatorControlTargetRequest* other) { + inline void Swap(Quaternion* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -11214,7 +11496,7 @@ class SetRateActuatorControlTargetRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateActuatorControlTargetRequest* other) { + void UnsafeArenaSwap(Quaternion* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11222,14 +11504,14 @@ class SetRateActuatorControlTargetRequest final : // implements Message ---------------------------------------------- - SetRateActuatorControlTargetRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateActuatorControlTargetRequest& from); + void CopyFrom(const Quaternion& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateActuatorControlTargetRequest& from) { - SetRateActuatorControlTargetRequest::MergeImpl(*this, from); + void MergeFrom( const Quaternion& from) { + Quaternion::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -11247,16 +11529,16 @@ class SetRateActuatorControlTargetRequest final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateActuatorControlTargetRequest* other); + void InternalSwap(Quaternion* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest"; + return "mavsdk.rpc.telemetry.Quaternion"; } protected: - explicit SetRateActuatorControlTargetRequest(::google::protobuf::Arena* arena); - SetRateActuatorControlTargetRequest(::google::protobuf::Arena* arena, const SetRateActuatorControlTargetRequest& from); + explicit Quaternion(::google::protobuf::Arena* arena); + Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); public: static const ClassData _class_data_; @@ -11269,25 +11551,69 @@ class SetRateActuatorControlTargetRequest final : // accessors ------------------------------------------------------- enum : int { - kRateHzFieldNumber = 1, + kWFieldNumber = 1, + kXFieldNumber = 2, + kYFieldNumber = 3, + kZFieldNumber = 4, + kTimestampUsFieldNumber = 5, }; - // double rate_hz = 1; - void clear_rate_hz() ; - double rate_hz() const; - void set_rate_hz(double value); + // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_w() ; + float w() const; + void set_w(float value); private: - double _internal_rate_hz() const; - void _internal_set_rate_hz(double value); + float _internal_w() const; + void _internal_set_w(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorControlTargetRequest) + // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_x() ; + float x() const; + void set_x(float value); + + private: + float _internal_x() const; + void _internal_set_x(float value); + + public: + // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_y() ; + float y() const; + void set_y(float value); + + private: + float _internal_y() const; + void _internal_set_y(float value); + + public: + // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_z() ; + float z() const; + void set_z(float value); + + private: + float _internal_z() const; + void _internal_set_z(float value); + + public: + // uint64 timestamp_us = 5; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); + + private: + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Quaternion) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 3, 5, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -11304,7 +11630,11 @@ class SetRateActuatorControlTargetRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double rate_hz_; + float w_; + float x_; + float y_; + float z_; + ::uint64_t timestamp_us_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -11312,26 +11642,26 @@ class SetRateActuatorControlTargetRequest final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class ScaledPressure final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ScaledPressure) */ { +class PositionNed final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionNed) */ { public: - inline ScaledPressure() : ScaledPressure(nullptr) {} - ~ScaledPressure() override; + inline PositionNed() : PositionNed(nullptr) {} + ~PositionNed() override; template - explicit PROTOBUF_CONSTEXPR ScaledPressure(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR PositionNed(::google::protobuf::internal::ConstantInitialized); - inline ScaledPressure(const ScaledPressure& from) - : ScaledPressure(nullptr, from) {} - ScaledPressure(ScaledPressure&& from) noexcept - : ScaledPressure() { + inline PositionNed(const PositionNed& from) + : PositionNed(nullptr, from) {} + PositionNed(PositionNed&& from) noexcept + : PositionNed() { *this = ::std::move(from); } - inline ScaledPressure& operator=(const ScaledPressure& from) { + inline PositionNed& operator=(const PositionNed& from) { CopyFrom(from); return *this; } - inline ScaledPressure& operator=(ScaledPressure&& from) noexcept { + inline PositionNed& operator=(PositionNed&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -11363,20 +11693,20 @@ class ScaledPressure final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ScaledPressure& default_instance() { + static const PositionNed& default_instance() { return *internal_default_instance(); } - static inline const ScaledPressure* internal_default_instance() { - return reinterpret_cast( - &_ScaledPressure_default_instance_); + static inline const PositionNed* internal_default_instance() { + return reinterpret_cast( + &_PositionNed_default_instance_); } static constexpr int kIndexInFileMessages = - 141; + 134; - friend void swap(ScaledPressure& a, ScaledPressure& b) { + friend void swap(PositionNed& a, PositionNed& b) { a.Swap(&b); } - inline void Swap(ScaledPressure* other) { + inline void Swap(PositionNed* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -11389,7 +11719,7 @@ class ScaledPressure final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ScaledPressure* other) { + void UnsafeArenaSwap(PositionNed* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11397,14 +11727,14 @@ class ScaledPressure final : // implements Message ---------------------------------------------- - ScaledPressure* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + PositionNed* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ScaledPressure& from); + void CopyFrom(const PositionNed& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ScaledPressure& from) { - ScaledPressure::MergeImpl(*this, from); + void MergeFrom( const PositionNed& from) { + PositionNed::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -11422,16 +11752,16 @@ class ScaledPressure final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ScaledPressure* other); + void InternalSwap(PositionNed* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.ScaledPressure"; + return "mavsdk.rpc.telemetry.PositionNed"; } protected: - explicit ScaledPressure(::google::protobuf::Arena* arena); - ScaledPressure(::google::protobuf::Arena* arena, const ScaledPressure& from); + explicit PositionNed(::google::protobuf::Arena* arena); + PositionNed(::google::protobuf::Arena* arena, const PositionNed& from); public: static const ClassData _class_data_; @@ -11444,69 +11774,47 @@ class ScaledPressure final : // accessors ------------------------------------------------------- enum : int { - kTimestampUsFieldNumber = 1, - kAbsolutePressureHpaFieldNumber = 2, - kDifferentialPressureHpaFieldNumber = 3, - kTemperatureDegFieldNumber = 4, - kDifferentialPressureTemperatureDegFieldNumber = 5, + kNorthMFieldNumber = 1, + kEastMFieldNumber = 2, + kDownMFieldNumber = 3, }; - // uint64 timestamp_us = 1; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); - - private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); - - public: - // float absolute_pressure_hpa = 2; - void clear_absolute_pressure_hpa() ; - float absolute_pressure_hpa() const; - void set_absolute_pressure_hpa(float value); - - private: - float _internal_absolute_pressure_hpa() const; - void _internal_set_absolute_pressure_hpa(float value); - - public: - // float differential_pressure_hpa = 3; - void clear_differential_pressure_hpa() ; - float differential_pressure_hpa() const; - void set_differential_pressure_hpa(float value); + // float north_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_north_m() ; + float north_m() const; + void set_north_m(float value); private: - float _internal_differential_pressure_hpa() const; - void _internal_set_differential_pressure_hpa(float value); + float _internal_north_m() const; + void _internal_set_north_m(float value); public: - // float temperature_deg = 4; - void clear_temperature_deg() ; - float temperature_deg() const; - void set_temperature_deg(float value); + // float east_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_east_m() ; + float east_m() const; + void set_east_m(float value); private: - float _internal_temperature_deg() const; - void _internal_set_temperature_deg(float value); + float _internal_east_m() const; + void _internal_set_east_m(float value); public: - // float differential_pressure_temperature_deg = 5; - void clear_differential_pressure_temperature_deg() ; - float differential_pressure_temperature_deg() const; - void set_differential_pressure_temperature_deg(float value); + // float down_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_down_m() ; + float down_m() const; + void set_down_m(float value); private: - float _internal_differential_pressure_temperature_deg() const; - void _internal_set_differential_pressure_temperature_deg(float value); + float _internal_down_m() const; + void _internal_set_down_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ScaledPressure) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionNed) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 5, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -11523,11 +11831,9 @@ class ScaledPressure final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::uint64_t timestamp_us_; - float absolute_pressure_hpa_; - float differential_pressure_hpa_; - float temperature_deg_; - float differential_pressure_temperature_deg_; + float north_m_; + float east_m_; + float down_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -11535,26 +11841,26 @@ class ScaledPressure final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class RcStatus final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatus) */ { +class PositionBody final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionBody) */ { public: - inline RcStatus() : RcStatus(nullptr) {} - ~RcStatus() override; + inline PositionBody() : PositionBody(nullptr) {} + ~PositionBody() override; template - explicit PROTOBUF_CONSTEXPR RcStatus(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR PositionBody(::google::protobuf::internal::ConstantInitialized); - inline RcStatus(const RcStatus& from) - : RcStatus(nullptr, from) {} - RcStatus(RcStatus&& from) noexcept - : RcStatus() { + inline PositionBody(const PositionBody& from) + : PositionBody(nullptr, from) {} + PositionBody(PositionBody&& from) noexcept + : PositionBody() { *this = ::std::move(from); } - inline RcStatus& operator=(const RcStatus& from) { + inline PositionBody& operator=(const PositionBody& from) { CopyFrom(from); return *this; } - inline RcStatus& operator=(RcStatus&& from) noexcept { + inline PositionBody& operator=(PositionBody&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -11586,20 +11892,20 @@ class RcStatus final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RcStatus& default_instance() { + static const PositionBody& default_instance() { return *internal_default_instance(); } - static inline const RcStatus* internal_default_instance() { - return reinterpret_cast( - &_RcStatus_default_instance_); + static inline const PositionBody* internal_default_instance() { + return reinterpret_cast( + &_PositionBody_default_instance_); } static constexpr int kIndexInFileMessages = - 132; + 130; - friend void swap(RcStatus& a, RcStatus& b) { + friend void swap(PositionBody& a, PositionBody& b) { a.Swap(&b); } - inline void Swap(RcStatus* other) { + inline void Swap(PositionBody* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -11612,7 +11918,7 @@ class RcStatus final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RcStatus* other) { + void UnsafeArenaSwap(PositionBody* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11620,14 +11926,14 @@ class RcStatus final : // implements Message ---------------------------------------------- - RcStatus* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + PositionBody* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RcStatus& from); + void CopyFrom(const PositionBody& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RcStatus& from) { - RcStatus::MergeImpl(*this, from); + void MergeFrom( const PositionBody& from) { + PositionBody::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -11645,16 +11951,16 @@ class RcStatus final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RcStatus* other); + void InternalSwap(PositionBody* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.RcStatus"; + return "mavsdk.rpc.telemetry.PositionBody"; } protected: - explicit RcStatus(::google::protobuf::Arena* arena); - RcStatus(::google::protobuf::Arena* arena, const RcStatus& from); + explicit PositionBody(::google::protobuf::Arena* arena); + PositionBody(::google::protobuf::Arena* arena, const PositionBody& from); public: static const ClassData _class_data_; @@ -11667,41 +11973,41 @@ class RcStatus final : // accessors ------------------------------------------------------- enum : int { - kWasAvailableOnceFieldNumber = 1, - kIsAvailableFieldNumber = 2, - kSignalStrengthPercentFieldNumber = 3, + kXMFieldNumber = 1, + kYMFieldNumber = 2, + kZMFieldNumber = 3, }; - // bool was_available_once = 1 [(.mavsdk.options.default_value) = "false"]; - void clear_was_available_once() ; - bool was_available_once() const; - void set_was_available_once(bool value); + // float x_m = 1; + void clear_x_m() ; + float x_m() const; + void set_x_m(float value); private: - bool _internal_was_available_once() const; - void _internal_set_was_available_once(bool value); + float _internal_x_m() const; + void _internal_set_x_m(float value); public: - // bool is_available = 2 [(.mavsdk.options.default_value) = "false"]; - void clear_is_available() ; - bool is_available() const; - void set_is_available(bool value); + // float y_m = 2; + void clear_y_m() ; + float y_m() const; + void set_y_m(float value); private: - bool _internal_is_available() const; - void _internal_set_is_available(bool value); + float _internal_y_m() const; + void _internal_set_y_m(float value); public: - // float signal_strength_percent = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_signal_strength_percent() ; - float signal_strength_percent() const; - void set_signal_strength_percent(float value); + // float z_m = 3; + void clear_z_m() ; + float z_m() const; + void set_z_m(float value); private: - float _internal_signal_strength_percent() const; - void _internal_set_signal_strength_percent(float value); + float _internal_z_m() const; + void _internal_set_z_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionBody) private: class _Internal; @@ -11724,9 +12030,9 @@ class RcStatus final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool was_available_once_; - bool is_available_; - float signal_strength_percent_; + float x_m_; + float y_m_; + float z_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -11734,26 +12040,26 @@ class RcStatus final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class RawGps final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RawGps) */ { +class Position final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Position) */ { public: - inline RawGps() : RawGps(nullptr) {} - ~RawGps() override; + inline Position() : Position(nullptr) {} + ~Position() override; template - explicit PROTOBUF_CONSTEXPR RawGps(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); - inline RawGps(const RawGps& from) - : RawGps(nullptr, from) {} - RawGps(RawGps&& from) noexcept - : RawGps() { + inline Position(const Position& from) + : Position(nullptr, from) {} + Position(Position&& from) noexcept + : Position() { *this = ::std::move(from); } - inline RawGps& operator=(const RawGps& from) { + inline Position& operator=(const Position& from) { CopyFrom(from); return *this; } - inline RawGps& operator=(RawGps&& from) noexcept { + inline Position& operator=(Position&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -11785,20 +12091,20 @@ class RawGps final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RawGps& default_instance() { + static const Position& default_instance() { return *internal_default_instance(); } - static inline const RawGps* internal_default_instance() { - return reinterpret_cast( - &_RawGps_default_instance_); + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 129; + 115; - friend void swap(RawGps& a, RawGps& b) { + friend void swap(Position& a, Position& b) { a.Swap(&b); } - inline void Swap(RawGps* other) { + inline void Swap(Position* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -11811,7 +12117,7 @@ class RawGps final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RawGps* other) { + void UnsafeArenaSwap(Position* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11819,14 +12125,14 @@ class RawGps final : // implements Message ---------------------------------------------- - RawGps* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Position* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RawGps& from); + void CopyFrom(const Position& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RawGps& from) { - RawGps::MergeImpl(*this, from); + void MergeFrom( const Position& from) { + Position::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -11844,16 +12150,16 @@ class RawGps final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RawGps* other); + void InternalSwap(Position* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.RawGps"; + return "mavsdk.rpc.telemetry.Position"; } protected: - explicit RawGps(::google::protobuf::Arena* arena); - RawGps(::google::protobuf::Arena* arena, const RawGps& from); + explicit Position(::google::protobuf::Arena* arena); + Position(::google::protobuf::Arena* arena, const Position& from); public: static const ClassData _class_data_; @@ -11866,32 +12172,12 @@ class RawGps final : // accessors ------------------------------------------------------- enum : int { - kTimestampUsFieldNumber = 1, - kLatitudeDegFieldNumber = 2, - kLongitudeDegFieldNumber = 3, - kAbsoluteAltitudeMFieldNumber = 4, - kHdopFieldNumber = 5, - kVdopFieldNumber = 6, - kVelocityMSFieldNumber = 7, - kCogDegFieldNumber = 8, - kAltitudeEllipsoidMFieldNumber = 9, - kHorizontalUncertaintyMFieldNumber = 10, - kVerticalUncertaintyMFieldNumber = 11, - kVelocityUncertaintyMSFieldNumber = 12, - kHeadingUncertaintyDegFieldNumber = 13, - kYawDegFieldNumber = 14, + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, + kRelativeAltitudeMFieldNumber = 4, }; - // uint64 timestamp_us = 1; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); - - private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); - - public: - // double latitude_deg = 2; + // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; void clear_latitude_deg() ; double latitude_deg() const; void set_latitude_deg(double value); @@ -11901,7 +12187,7 @@ class RawGps final : void _internal_set_latitude_deg(double value); public: - // double longitude_deg = 3; + // double longitude_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; void clear_longitude_deg() ; double longitude_deg() const; void set_longitude_deg(double value); @@ -11911,7 +12197,7 @@ class RawGps final : void _internal_set_longitude_deg(double value); public: - // float absolute_altitude_m = 4; + // float absolute_altitude_m = 3 [(.mavsdk.options.default_value) = "NaN"]; void clear_absolute_altitude_m() ; float absolute_altitude_m() const; void set_absolute_altitude_m(float value); @@ -11921,113 +12207,23 @@ class RawGps final : void _internal_set_absolute_altitude_m(float value); public: - // float hdop = 5; - void clear_hdop() ; - float hdop() const; - void set_hdop(float value); - - private: - float _internal_hdop() const; - void _internal_set_hdop(float value); - - public: - // float vdop = 6; - void clear_vdop() ; - float vdop() const; - void set_vdop(float value); - - private: - float _internal_vdop() const; - void _internal_set_vdop(float value); - - public: - // float velocity_m_s = 7; - void clear_velocity_m_s() ; - float velocity_m_s() const; - void set_velocity_m_s(float value); - - private: - float _internal_velocity_m_s() const; - void _internal_set_velocity_m_s(float value); - - public: - // float cog_deg = 8; - void clear_cog_deg() ; - float cog_deg() const; - void set_cog_deg(float value); - - private: - float _internal_cog_deg() const; - void _internal_set_cog_deg(float value); - - public: - // float altitude_ellipsoid_m = 9; - void clear_altitude_ellipsoid_m() ; - float altitude_ellipsoid_m() const; - void set_altitude_ellipsoid_m(float value); - - private: - float _internal_altitude_ellipsoid_m() const; - void _internal_set_altitude_ellipsoid_m(float value); - - public: - // float horizontal_uncertainty_m = 10; - void clear_horizontal_uncertainty_m() ; - float horizontal_uncertainty_m() const; - void set_horizontal_uncertainty_m(float value); - - private: - float _internal_horizontal_uncertainty_m() const; - void _internal_set_horizontal_uncertainty_m(float value); - - public: - // float vertical_uncertainty_m = 11; - void clear_vertical_uncertainty_m() ; - float vertical_uncertainty_m() const; - void set_vertical_uncertainty_m(float value); - - private: - float _internal_vertical_uncertainty_m() const; - void _internal_set_vertical_uncertainty_m(float value); - - public: - // float velocity_uncertainty_m_s = 12; - void clear_velocity_uncertainty_m_s() ; - float velocity_uncertainty_m_s() const; - void set_velocity_uncertainty_m_s(float value); - - private: - float _internal_velocity_uncertainty_m_s() const; - void _internal_set_velocity_uncertainty_m_s(float value); - - public: - // float heading_uncertainty_deg = 13; - void clear_heading_uncertainty_deg() ; - float heading_uncertainty_deg() const; - void set_heading_uncertainty_deg(float value); - - private: - float _internal_heading_uncertainty_deg() const; - void _internal_set_heading_uncertainty_deg(float value); - - public: - // float yaw_deg = 14; - void clear_yaw_deg() ; - float yaw_deg() const; - void set_yaw_deg(float value); + // float relative_altitude_m = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_relative_altitude_m() ; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); private: - float _internal_yaw_deg() const; - void _internal_set_yaw_deg(float value); + float _internal_relative_altitude_m() const; + void _internal_set_relative_altitude_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RawGps) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Position) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 4, 14, 0, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -12044,20 +12240,10 @@ class RawGps final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::uint64_t timestamp_us_; double latitude_deg_; double longitude_deg_; float absolute_altitude_m_; - float hdop_; - float vdop_; - float velocity_m_s_; - float cog_deg_; - float altitude_ellipsoid_m_; - float horizontal_uncertainty_m_; - float vertical_uncertainty_m_; - float velocity_uncertainty_m_s_; - float heading_uncertainty_deg_; - float yaw_deg_; + float relative_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -12065,26 +12251,26 @@ class RawGps final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Quaternion final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Quaternion) */ { +class MagneticFieldFrd final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.MagneticFieldFrd) */ { public: - inline Quaternion() : Quaternion(nullptr) {} - ~Quaternion() override; + inline MagneticFieldFrd() : MagneticFieldFrd(nullptr) {} + ~MagneticFieldFrd() override; template - explicit PROTOBUF_CONSTEXPR Quaternion(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR MagneticFieldFrd(::google::protobuf::internal::ConstantInitialized); - inline Quaternion(const Quaternion& from) - : Quaternion(nullptr, from) {} - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + inline MagneticFieldFrd(const MagneticFieldFrd& from) + : MagneticFieldFrd(nullptr, from) {} + MagneticFieldFrd(MagneticFieldFrd&& from) noexcept + : MagneticFieldFrd() { *this = ::std::move(from); } - inline Quaternion& operator=(const Quaternion& from) { + inline MagneticFieldFrd& operator=(const MagneticFieldFrd& from) { CopyFrom(from); return *this; } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline MagneticFieldFrd& operator=(MagneticFieldFrd&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -12116,20 +12302,20 @@ class Quaternion final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Quaternion& default_instance() { + static const MagneticFieldFrd& default_instance() { return *internal_default_instance(); } - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const MagneticFieldFrd* internal_default_instance() { + return reinterpret_cast( + &_MagneticFieldFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 125; + 141; - friend void swap(Quaternion& a, Quaternion& b) { + friend void swap(MagneticFieldFrd& a, MagneticFieldFrd& b) { a.Swap(&b); } - inline void Swap(Quaternion* other) { + inline void Swap(MagneticFieldFrd* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -12142,7 +12328,7 @@ class Quaternion final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Quaternion* other) { + void UnsafeArenaSwap(MagneticFieldFrd* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -12150,14 +12336,14 @@ class Quaternion final : // implements Message ---------------------------------------------- - Quaternion* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + MagneticFieldFrd* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Quaternion& from); + void CopyFrom(const MagneticFieldFrd& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Quaternion& from) { - Quaternion::MergeImpl(*this, from); + void MergeFrom( const MagneticFieldFrd& from) { + MagneticFieldFrd::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -12175,16 +12361,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(MagneticFieldFrd* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Quaternion"; + return "mavsdk.rpc.telemetry.MagneticFieldFrd"; } protected: - explicit Quaternion(::google::protobuf::Arena* arena); - Quaternion(::google::protobuf::Arena* arena, const Quaternion& from); + explicit MagneticFieldFrd(::google::protobuf::Arena* arena); + MagneticFieldFrd(::google::protobuf::Arena* arena, const MagneticFieldFrd& from); public: static const ClassData _class_data_; @@ -12197,69 +12383,47 @@ class Quaternion final : // accessors ------------------------------------------------------- enum : int { - kWFieldNumber = 1, - kXFieldNumber = 2, - kYFieldNumber = 3, - kZFieldNumber = 4, - kTimestampUsFieldNumber = 5, + kForwardGaussFieldNumber = 1, + kRightGaussFieldNumber = 2, + kDownGaussFieldNumber = 3, }; - // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_w() ; - float w() const; - void set_w(float value); - - private: - float _internal_w() const; - void _internal_set_w(float value); - - public: - // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_x() ; - float x() const; - void set_x(float value); - - private: - float _internal_x() const; - void _internal_set_x(float value); - - public: - // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_y() ; - float y() const; - void set_y(float value); + // float forward_gauss = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_forward_gauss() ; + float forward_gauss() const; + void set_forward_gauss(float value); private: - float _internal_y() const; - void _internal_set_y(float value); + float _internal_forward_gauss() const; + void _internal_set_forward_gauss(float value); public: - // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; - void clear_z() ; - float z() const; - void set_z(float value); + // float right_gauss = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_right_gauss() ; + float right_gauss() const; + void set_right_gauss(float value); private: - float _internal_z() const; - void _internal_set_z(float value); + float _internal_right_gauss() const; + void _internal_set_right_gauss(float value); public: - // uint64 timestamp_us = 5; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); + // float down_gauss = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_down_gauss() ; + float down_gauss() const; + void set_down_gauss(float value); private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); + float _internal_down_gauss() const; + void _internal_set_down_gauss(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.MagneticFieldFrd) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 5, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -12276,11 +12440,9 @@ 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_; - ::uint64_t timestamp_us_; + float forward_gauss_; + float right_gauss_; + float down_gauss_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -12288,26 +12450,26 @@ class Quaternion final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class PositionNed final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionNed) */ { +class LandedStateResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.LandedStateResponse) */ { public: - inline PositionNed() : PositionNed(nullptr) {} - ~PositionNed() override; + inline LandedStateResponse() : LandedStateResponse(nullptr) {} + ~LandedStateResponse() override; template - explicit PROTOBUF_CONSTEXPR PositionNed(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR LandedStateResponse(::google::protobuf::internal::ConstantInitialized); - inline PositionNed(const PositionNed& from) - : PositionNed(nullptr, from) {} - PositionNed(PositionNed&& from) noexcept - : PositionNed() { + inline LandedStateResponse(const LandedStateResponse& from) + : LandedStateResponse(nullptr, from) {} + LandedStateResponse(LandedStateResponse&& from) noexcept + : LandedStateResponse() { *this = ::std::move(from); } - inline PositionNed& operator=(const PositionNed& from) { + inline LandedStateResponse& operator=(const LandedStateResponse& from) { CopyFrom(from); return *this; } - inline PositionNed& operator=(PositionNed&& from) noexcept { + inline LandedStateResponse& operator=(LandedStateResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -12339,20 +12501,20 @@ class PositionNed final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PositionNed& default_instance() { + static const LandedStateResponse& default_instance() { return *internal_default_instance(); } - static inline const PositionNed* internal_default_instance() { - return reinterpret_cast( - &_PositionNed_default_instance_); + static inline const LandedStateResponse* internal_default_instance() { + return reinterpret_cast( + &_LandedStateResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 142; + 7; - friend void swap(PositionNed& a, PositionNed& b) { + friend void swap(LandedStateResponse& a, LandedStateResponse& b) { a.Swap(&b); } - inline void Swap(PositionNed* other) { + inline void Swap(LandedStateResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -12365,7 +12527,7 @@ class PositionNed final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PositionNed* other) { + void UnsafeArenaSwap(LandedStateResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -12373,14 +12535,14 @@ class PositionNed final : // implements Message ---------------------------------------------- - PositionNed* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + LandedStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PositionNed& from); + void CopyFrom(const LandedStateResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const PositionNed& from) { - PositionNed::MergeImpl(*this, from); + void MergeFrom( const LandedStateResponse& from) { + LandedStateResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -12398,16 +12560,16 @@ class PositionNed final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(PositionNed* other); + void InternalSwap(LandedStateResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.PositionNed"; + return "mavsdk.rpc.telemetry.LandedStateResponse"; } protected: - explicit PositionNed(::google::protobuf::Arena* arena); - PositionNed(::google::protobuf::Arena* arena, const PositionNed& from); + explicit LandedStateResponse(::google::protobuf::Arena* arena); + LandedStateResponse(::google::protobuf::Arena* arena, const LandedStateResponse& from); public: static const ClassData _class_data_; @@ -12420,47 +12582,25 @@ class PositionNed final : // accessors ------------------------------------------------------- enum : int { - kNorthMFieldNumber = 1, - kEastMFieldNumber = 2, - kDownMFieldNumber = 3, + kLandedStateFieldNumber = 1, }; - // float north_m = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_north_m() ; - float north_m() const; - void set_north_m(float value); - - private: - float _internal_north_m() const; - void _internal_set_north_m(float value); - - public: - // float east_m = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_east_m() ; - float east_m() const; - void set_east_m(float value); - - private: - float _internal_east_m() const; - void _internal_set_east_m(float value); - - public: - // float down_m = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_down_m() ; - float down_m() const; - void set_down_m(float value); + // .mavsdk.rpc.telemetry.LandedState landed_state = 1; + void clear_landed_state() ; + ::mavsdk::rpc::telemetry::LandedState landed_state() const; + void set_landed_state(::mavsdk::rpc::telemetry::LandedState value); private: - float _internal_down_m() const; - void _internal_set_down_m(float value); + ::mavsdk::rpc::telemetry::LandedState _internal_landed_state() const; + void _internal_set_landed_state(::mavsdk::rpc::telemetry::LandedState value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionNed) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.LandedStateResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -12477,9 +12617,7 @@ class PositionNed final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float north_m_; - float east_m_; - float down_m_; + int landed_state_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -12487,26 +12625,26 @@ class PositionNed final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class PositionBody final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionBody) */ { +class InAirResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.InAirResponse) */ { public: - inline PositionBody() : PositionBody(nullptr) {} - ~PositionBody() override; + inline InAirResponse() : InAirResponse(nullptr) {} + ~InAirResponse() override; template - explicit PROTOBUF_CONSTEXPR PositionBody(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR InAirResponse(::google::protobuf::internal::ConstantInitialized); - inline PositionBody(const PositionBody& from) - : PositionBody(nullptr, from) {} - PositionBody(PositionBody&& from) noexcept - : PositionBody() { + inline InAirResponse(const InAirResponse& from) + : InAirResponse(nullptr, from) {} + InAirResponse(InAirResponse&& from) noexcept + : InAirResponse() { *this = ::std::move(from); } - inline PositionBody& operator=(const PositionBody& from) { + inline InAirResponse& operator=(const InAirResponse& from) { CopyFrom(from); return *this; } - inline PositionBody& operator=(PositionBody&& from) noexcept { + inline InAirResponse& operator=(InAirResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -12538,20 +12676,20 @@ class PositionBody final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PositionBody& default_instance() { + static const InAirResponse& default_instance() { return *internal_default_instance(); } - static inline const PositionBody* internal_default_instance() { - return reinterpret_cast( - &_PositionBody_default_instance_); + static inline const InAirResponse* internal_default_instance() { + return reinterpret_cast( + &_InAirResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 138; + 5; - friend void swap(PositionBody& a, PositionBody& b) { + friend void swap(InAirResponse& a, InAirResponse& b) { a.Swap(&b); } - inline void Swap(PositionBody* other) { + inline void Swap(InAirResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -12564,7 +12702,7 @@ class PositionBody final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PositionBody* other) { + void UnsafeArenaSwap(InAirResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -12572,14 +12710,14 @@ class PositionBody final : // implements Message ---------------------------------------------- - PositionBody* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + InAirResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PositionBody& from); + void CopyFrom(const InAirResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const PositionBody& from) { - PositionBody::MergeImpl(*this, from); + void MergeFrom( const InAirResponse& from) { + InAirResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -12597,16 +12735,16 @@ class PositionBody final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(PositionBody* other); + void InternalSwap(InAirResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.PositionBody"; + return "mavsdk.rpc.telemetry.InAirResponse"; } protected: - explicit PositionBody(::google::protobuf::Arena* arena); - PositionBody(::google::protobuf::Arena* arena, const PositionBody& from); + explicit InAirResponse(::google::protobuf::Arena* arena); + InAirResponse(::google::protobuf::Arena* arena, const InAirResponse& from); public: static const ClassData _class_data_; @@ -12619,47 +12757,25 @@ class PositionBody final : // accessors ------------------------------------------------------- enum : int { - kXMFieldNumber = 1, - kYMFieldNumber = 2, - kZMFieldNumber = 3, + kIsInAirFieldNumber = 1, }; - // float x_m = 1; - void clear_x_m() ; - float x_m() const; - void set_x_m(float value); - - private: - float _internal_x_m() const; - void _internal_set_x_m(float value); - - public: - // float y_m = 2; - void clear_y_m() ; - float y_m() const; - void set_y_m(float value); - - private: - float _internal_y_m() const; - void _internal_set_y_m(float value); - - public: - // float z_m = 3; - void clear_z_m() ; - float z_m() const; - void set_z_m(float value); + // bool is_in_air = 1; + void clear_is_in_air() ; + bool is_in_air() const; + void set_is_in_air(bool value); private: - float _internal_z_m() const; - void _internal_set_z_m(float value); + bool _internal_is_in_air() const; + void _internal_set_is_in_air(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionBody) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.InAirResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -12676,9 +12792,7 @@ class PositionBody final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float x_m_; - float y_m_; - float z_m_; + bool is_in_air_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -12686,26 +12800,26 @@ class PositionBody final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Position final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Position) */ { +class HealthAllOkResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HealthAllOkResponse) */ { public: - inline Position() : Position(nullptr) {} - ~Position() override; + inline HealthAllOkResponse() : HealthAllOkResponse(nullptr) {} + ~HealthAllOkResponse() override; template - explicit PROTOBUF_CONSTEXPR Position(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR HealthAllOkResponse(::google::protobuf::internal::ConstantInitialized); - inline Position(const Position& from) - : Position(nullptr, from) {} - Position(Position&& from) noexcept - : Position() { + inline HealthAllOkResponse(const HealthAllOkResponse& from) + : HealthAllOkResponse(nullptr, from) {} + HealthAllOkResponse(HealthAllOkResponse&& from) noexcept + : HealthAllOkResponse() { *this = ::std::move(from); } - inline Position& operator=(const Position& from) { + inline HealthAllOkResponse& operator=(const HealthAllOkResponse& from) { CopyFrom(from); return *this; } - inline Position& operator=(Position&& from) noexcept { + inline HealthAllOkResponse& operator=(HealthAllOkResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -12737,20 +12851,20 @@ class Position final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Position& default_instance() { + static const HealthAllOkResponse& default_instance() { return *internal_default_instance(); } - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const HealthAllOkResponse* internal_default_instance() { + return reinterpret_cast( + &_HealthAllOkResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 123; + 53; - friend void swap(Position& a, Position& b) { + friend void swap(HealthAllOkResponse& a, HealthAllOkResponse& b) { a.Swap(&b); } - inline void Swap(Position* other) { + inline void Swap(HealthAllOkResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -12763,7 +12877,7 @@ class Position final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Position* other) { + void UnsafeArenaSwap(HealthAllOkResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -12771,14 +12885,14 @@ class Position final : // implements Message ---------------------------------------------- - Position* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + HealthAllOkResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Position& from); + void CopyFrom(const HealthAllOkResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Position& from) { - Position::MergeImpl(*this, from); + void MergeFrom( const HealthAllOkResponse& from) { + HealthAllOkResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -12796,16 +12910,16 @@ class Position final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Position* other); + void InternalSwap(HealthAllOkResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Position"; + return "mavsdk.rpc.telemetry.HealthAllOkResponse"; } protected: - explicit Position(::google::protobuf::Arena* arena); - Position(::google::protobuf::Arena* arena, const Position& from); + explicit HealthAllOkResponse(::google::protobuf::Arena* arena); + HealthAllOkResponse(::google::protobuf::Arena* arena, const HealthAllOkResponse& from); public: static const ClassData _class_data_; @@ -12818,58 +12932,25 @@ class Position final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, - kRelativeAltitudeMFieldNumber = 4, + kIsHealthAllOkFieldNumber = 1, }; - // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - 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 [(.mavsdk.options.default_value) = "NaN"]; - 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 [(.mavsdk.options.default_value) = "NaN"]; - 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 [(.mavsdk.options.default_value) = "NaN"]; - void clear_relative_altitude_m() ; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); + // bool is_health_all_ok = 1; + void clear_is_health_all_ok() ; + bool is_health_all_ok() const; + void set_is_health_all_ok(bool value); private: - float _internal_relative_altitude_m() const; - void _internal_set_relative_altitude_m(float value); + bool _internal_is_health_all_ok() const; + void _internal_set_is_health_all_ok(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HealthAllOkResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -12886,10 +12967,7 @@ 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_; + bool is_health_all_ok_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -12897,26 +12975,26 @@ class Position final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class MagneticFieldFrd final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.MagneticFieldFrd) */ { +class Health final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Health) */ { public: - inline MagneticFieldFrd() : MagneticFieldFrd(nullptr) {} - ~MagneticFieldFrd() override; + inline Health() : Health(nullptr) {} + ~Health() override; template - explicit PROTOBUF_CONSTEXPR MagneticFieldFrd(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Health(::google::protobuf::internal::ConstantInitialized); - inline MagneticFieldFrd(const MagneticFieldFrd& from) - : MagneticFieldFrd(nullptr, from) {} - MagneticFieldFrd(MagneticFieldFrd&& from) noexcept - : MagneticFieldFrd() { + inline Health(const Health& from) + : Health(nullptr, from) {} + Health(Health&& from) noexcept + : Health() { *this = ::std::move(from); } - inline MagneticFieldFrd& operator=(const MagneticFieldFrd& from) { + inline Health& operator=(const Health& from) { CopyFrom(from); return *this; } - inline MagneticFieldFrd& operator=(MagneticFieldFrd&& from) noexcept { + inline Health& operator=(Health&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -12948,20 +13026,20 @@ class MagneticFieldFrd final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const MagneticFieldFrd& default_instance() { + static const Health& default_instance() { return *internal_default_instance(); } - static inline const MagneticFieldFrd* internal_default_instance() { - return reinterpret_cast( - &_MagneticFieldFrd_default_instance_); + static inline const Health* internal_default_instance() { + return reinterpret_cast( + &_Health_default_instance_); } static constexpr int kIndexInFileMessages = - 149; + 123; - friend void swap(MagneticFieldFrd& a, MagneticFieldFrd& b) { + friend void swap(Health& a, Health& b) { a.Swap(&b); } - inline void Swap(MagneticFieldFrd* other) { + inline void Swap(Health* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -12974,7 +13052,7 @@ class MagneticFieldFrd final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(MagneticFieldFrd* other) { + void UnsafeArenaSwap(Health* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -12982,14 +13060,14 @@ class MagneticFieldFrd final : // implements Message ---------------------------------------------- - MagneticFieldFrd* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Health* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const MagneticFieldFrd& from); + void CopyFrom(const Health& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const MagneticFieldFrd& from) { - MagneticFieldFrd::MergeImpl(*this, from); + void MergeFrom( const Health& from) { + Health::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -13007,16 +13085,16 @@ class MagneticFieldFrd final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(MagneticFieldFrd* other); + void InternalSwap(Health* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.MagneticFieldFrd"; + return "mavsdk.rpc.telemetry.Health"; } protected: - explicit MagneticFieldFrd(::google::protobuf::Arena* arena); - MagneticFieldFrd(::google::protobuf::Arena* arena, const MagneticFieldFrd& from); + explicit Health(::google::protobuf::Arena* arena); + Health(::google::protobuf::Arena* arena, const Health& from); public: static const ClassData _class_data_; @@ -13029,47 +13107,91 @@ class MagneticFieldFrd final : // accessors ------------------------------------------------------- enum : int { - kForwardGaussFieldNumber = 1, - kRightGaussFieldNumber = 2, - kDownGaussFieldNumber = 3, + kIsGyrometerCalibrationOkFieldNumber = 1, + kIsAccelerometerCalibrationOkFieldNumber = 2, + kIsMagnetometerCalibrationOkFieldNumber = 3, + kIsLocalPositionOkFieldNumber = 5, + kIsGlobalPositionOkFieldNumber = 6, + kIsHomePositionOkFieldNumber = 7, + kIsArmableFieldNumber = 8, }; - // float forward_gauss = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_forward_gauss() ; - float forward_gauss() const; - void set_forward_gauss(float value); + // bool is_gyrometer_calibration_ok = 1 [(.mavsdk.options.default_value) = "false"]; + void clear_is_gyrometer_calibration_ok() ; + bool is_gyrometer_calibration_ok() const; + void set_is_gyrometer_calibration_ok(bool value); private: - float _internal_forward_gauss() const; - void _internal_set_forward_gauss(float value); + bool _internal_is_gyrometer_calibration_ok() const; + void _internal_set_is_gyrometer_calibration_ok(bool value); public: - // float right_gauss = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_right_gauss() ; - float right_gauss() const; - void set_right_gauss(float value); + // bool is_accelerometer_calibration_ok = 2 [(.mavsdk.options.default_value) = "false"]; + void clear_is_accelerometer_calibration_ok() ; + bool is_accelerometer_calibration_ok() const; + void set_is_accelerometer_calibration_ok(bool value); private: - float _internal_right_gauss() const; - void _internal_set_right_gauss(float value); + bool _internal_is_accelerometer_calibration_ok() const; + void _internal_set_is_accelerometer_calibration_ok(bool value); public: - // float down_gauss = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_down_gauss() ; - float down_gauss() const; - void set_down_gauss(float value); + // bool is_magnetometer_calibration_ok = 3 [(.mavsdk.options.default_value) = "false"]; + void clear_is_magnetometer_calibration_ok() ; + bool is_magnetometer_calibration_ok() const; + void set_is_magnetometer_calibration_ok(bool value); private: - float _internal_down_gauss() const; - void _internal_set_down_gauss(float value); + bool _internal_is_magnetometer_calibration_ok() const; + void _internal_set_is_magnetometer_calibration_ok(bool value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.MagneticFieldFrd) + // bool is_local_position_ok = 5 [(.mavsdk.options.default_value) = "false"]; + void clear_is_local_position_ok() ; + bool is_local_position_ok() const; + void set_is_local_position_ok(bool value); + + private: + bool _internal_is_local_position_ok() const; + void _internal_set_is_local_position_ok(bool value); + + public: + // bool is_global_position_ok = 6 [(.mavsdk.options.default_value) = "false"]; + void clear_is_global_position_ok() ; + bool is_global_position_ok() const; + void set_is_global_position_ok(bool value); + + private: + bool _internal_is_global_position_ok() const; + void _internal_set_is_global_position_ok(bool value); + + public: + // bool is_home_position_ok = 7 [(.mavsdk.options.default_value) = "false"]; + void clear_is_home_position_ok() ; + bool is_home_position_ok() const; + void set_is_home_position_ok(bool value); + + private: + bool _internal_is_home_position_ok() const; + void _internal_set_is_home_position_ok(bool value); + + public: + // bool is_armable = 8 [(.mavsdk.options.default_value) = "false"]; + void clear_is_armable() ; + bool is_armable() const; + void set_is_armable(bool value); + + private: + bool _internal_is_armable() const; + void _internal_set_is_armable(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Health) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 3, 7, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -13086,9 +13208,13 @@ class MagneticFieldFrd final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float forward_gauss_; - float right_gauss_; - float down_gauss_; + bool is_gyrometer_calibration_ok_; + bool is_accelerometer_calibration_ok_; + bool is_magnetometer_calibration_ok_; + bool is_local_position_ok_; + bool is_global_position_ok_; + bool is_home_position_ok_; + bool is_armable_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -13096,26 +13222,26 @@ class MagneticFieldFrd final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class LandedStateResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.LandedStateResponse) */ { +class Heading final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Heading) */ { public: - inline LandedStateResponse() : LandedStateResponse(nullptr) {} - ~LandedStateResponse() override; + inline Heading() : Heading(nullptr) {} + ~Heading() override; template - explicit PROTOBUF_CONSTEXPR LandedStateResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Heading(::google::protobuf::internal::ConstantInitialized); - inline LandedStateResponse(const LandedStateResponse& from) - : LandedStateResponse(nullptr, from) {} - LandedStateResponse(LandedStateResponse&& from) noexcept - : LandedStateResponse() { + inline Heading(const Heading& from) + : Heading(nullptr, from) {} + Heading(Heading&& from) noexcept + : Heading() { *this = ::std::move(from); } - inline LandedStateResponse& operator=(const LandedStateResponse& from) { + inline Heading& operator=(const Heading& from) { CopyFrom(from); return *this; } - inline LandedStateResponse& operator=(LandedStateResponse&& from) noexcept { + inline Heading& operator=(Heading&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -13147,20 +13273,20 @@ class LandedStateResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const LandedStateResponse& default_instance() { + static const Heading& default_instance() { return *internal_default_instance(); } - static inline const LandedStateResponse* internal_default_instance() { - return reinterpret_cast( - &_LandedStateResponse_default_instance_); + static inline const Heading* internal_default_instance() { + return reinterpret_cast( + &_Heading_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 116; - friend void swap(LandedStateResponse& a, LandedStateResponse& b) { + friend void swap(Heading& a, Heading& b) { a.Swap(&b); } - inline void Swap(LandedStateResponse* other) { + inline void Swap(Heading* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -13173,7 +13299,7 @@ class LandedStateResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(LandedStateResponse* other) { + void UnsafeArenaSwap(Heading* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -13181,14 +13307,14 @@ class LandedStateResponse final : // implements Message ---------------------------------------------- - LandedStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Heading* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const LandedStateResponse& from); + void CopyFrom(const Heading& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const LandedStateResponse& from) { - LandedStateResponse::MergeImpl(*this, from); + void MergeFrom( const Heading& from) { + Heading::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -13206,16 +13332,16 @@ class LandedStateResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(LandedStateResponse* other); + void InternalSwap(Heading* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.LandedStateResponse"; + return "mavsdk.rpc.telemetry.Heading"; } protected: - explicit LandedStateResponse(::google::protobuf::Arena* arena); - LandedStateResponse(::google::protobuf::Arena* arena, const LandedStateResponse& from); + explicit Heading(::google::protobuf::Arena* arena); + Heading(::google::protobuf::Arena* arena, const Heading& from); public: static const ClassData _class_data_; @@ -13228,19 +13354,19 @@ class LandedStateResponse final : // accessors ------------------------------------------------------- enum : int { - kLandedStateFieldNumber = 1, + kHeadingDegFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.LandedState landed_state = 1; - void clear_landed_state() ; - ::mavsdk::rpc::telemetry::LandedState landed_state() const; - void set_landed_state(::mavsdk::rpc::telemetry::LandedState value); + // double heading_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_heading_deg() ; + double heading_deg() const; + void set_heading_deg(double value); private: - ::mavsdk::rpc::telemetry::LandedState _internal_landed_state() const; - void _internal_set_landed_state(::mavsdk::rpc::telemetry::LandedState value); + double _internal_heading_deg() const; + void _internal_set_heading_deg(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.LandedStateResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Heading) private: class _Internal; @@ -13263,7 +13389,7 @@ class LandedStateResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int landed_state_; + double heading_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -13271,26 +13397,26 @@ class LandedStateResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class InAirResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.InAirResponse) */ { +class GroundTruth final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GroundTruth) */ { public: - inline InAirResponse() : InAirResponse(nullptr) {} - ~InAirResponse() override; + inline GroundTruth() : GroundTruth(nullptr) {} + ~GroundTruth() override; template - explicit PROTOBUF_CONSTEXPR InAirResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GroundTruth(::google::protobuf::internal::ConstantInitialized); - inline InAirResponse(const InAirResponse& from) - : InAirResponse(nullptr, from) {} - InAirResponse(InAirResponse&& from) noexcept - : InAirResponse() { + inline GroundTruth(const GroundTruth& from) + : GroundTruth(nullptr, from) {} + GroundTruth(GroundTruth&& from) noexcept + : GroundTruth() { *this = ::std::move(from); } - inline InAirResponse& operator=(const InAirResponse& from) { + inline GroundTruth& operator=(const GroundTruth& from) { CopyFrom(from); return *this; } - inline InAirResponse& operator=(InAirResponse&& from) noexcept { + inline GroundTruth& operator=(GroundTruth&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -13322,20 +13448,20 @@ class InAirResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const InAirResponse& default_instance() { + static const GroundTruth& default_instance() { return *internal_default_instance(); } - static inline const InAirResponse* internal_default_instance() { - return reinterpret_cast( - &_InAirResponse_default_instance_); + static inline const GroundTruth* internal_default_instance() { + return reinterpret_cast( + &_GroundTruth_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 137; - friend void swap(InAirResponse& a, InAirResponse& b) { + friend void swap(GroundTruth& a, GroundTruth& b) { a.Swap(&b); } - inline void Swap(InAirResponse* other) { + inline void Swap(GroundTruth* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -13348,7 +13474,7 @@ class InAirResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(InAirResponse* other) { + void UnsafeArenaSwap(GroundTruth* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -13356,14 +13482,14 @@ class InAirResponse final : // implements Message ---------------------------------------------- - InAirResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GroundTruth* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const InAirResponse& from); + void CopyFrom(const GroundTruth& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const InAirResponse& from) { - InAirResponse::MergeImpl(*this, from); + void MergeFrom( const GroundTruth& from) { + GroundTruth::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -13381,16 +13507,16 @@ class InAirResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(InAirResponse* other); + void InternalSwap(GroundTruth* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.InAirResponse"; + return "mavsdk.rpc.telemetry.GroundTruth"; } protected: - explicit InAirResponse(::google::protobuf::Arena* arena); - InAirResponse(::google::protobuf::Arena* arena, const InAirResponse& from); + explicit GroundTruth(::google::protobuf::Arena* arena); + GroundTruth(::google::protobuf::Arena* arena, const GroundTruth& from); public: static const ClassData _class_data_; @@ -13403,25 +13529,47 @@ class InAirResponse final : // accessors ------------------------------------------------------- enum : int { - kIsInAirFieldNumber = 1, + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAbsoluteAltitudeMFieldNumber = 3, }; - // bool is_in_air = 1; - void clear_is_in_air() ; - bool is_in_air() const; - void set_is_in_air(bool value); + // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); private: - bool _internal_is_in_air() const; - void _internal_set_is_in_air(bool value); + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.InAirResponse) + // double longitude_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + 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 [(.mavsdk.options.default_value) = "NaN"]; + 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: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GroundTruth) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -13438,7 +13586,9 @@ class InAirResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool is_in_air_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -13446,26 +13596,26 @@ class InAirResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class HealthAllOkResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HealthAllOkResponse) */ { +class GpsInfo final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfo) */ { public: - inline HealthAllOkResponse() : HealthAllOkResponse(nullptr) {} - ~HealthAllOkResponse() override; + inline GpsInfo() : GpsInfo(nullptr) {} + ~GpsInfo() override; template - explicit PROTOBUF_CONSTEXPR HealthAllOkResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GpsInfo(::google::protobuf::internal::ConstantInitialized); - inline HealthAllOkResponse(const HealthAllOkResponse& from) - : HealthAllOkResponse(nullptr, from) {} - HealthAllOkResponse(HealthAllOkResponse&& from) noexcept - : HealthAllOkResponse() { + inline GpsInfo(const GpsInfo& from) + : GpsInfo(nullptr, from) {} + GpsInfo(GpsInfo&& from) noexcept + : GpsInfo() { *this = ::std::move(from); } - inline HealthAllOkResponse& operator=(const HealthAllOkResponse& from) { + inline GpsInfo& operator=(const GpsInfo& from) { CopyFrom(from); return *this; } - inline HealthAllOkResponse& operator=(HealthAllOkResponse&& from) noexcept { + inline GpsInfo& operator=(GpsInfo&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -13497,20 +13647,20 @@ class HealthAllOkResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const HealthAllOkResponse& default_instance() { + static const GpsInfo& default_instance() { return *internal_default_instance(); } - static inline const HealthAllOkResponse* internal_default_instance() { - return reinterpret_cast( - &_HealthAllOkResponse_default_instance_); + static inline const GpsInfo* internal_default_instance() { + return reinterpret_cast( + &_GpsInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 57; + 120; - friend void swap(HealthAllOkResponse& a, HealthAllOkResponse& b) { + friend void swap(GpsInfo& a, GpsInfo& b) { a.Swap(&b); } - inline void Swap(HealthAllOkResponse* other) { + inline void Swap(GpsInfo* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -13523,7 +13673,7 @@ class HealthAllOkResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(HealthAllOkResponse* other) { + void UnsafeArenaSwap(GpsInfo* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -13531,14 +13681,14 @@ class HealthAllOkResponse final : // implements Message ---------------------------------------------- - HealthAllOkResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GpsInfo* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const HealthAllOkResponse& from); + void CopyFrom(const GpsInfo& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const HealthAllOkResponse& from) { - HealthAllOkResponse::MergeImpl(*this, from); + void MergeFrom( const GpsInfo& from) { + GpsInfo::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -13556,16 +13706,16 @@ class HealthAllOkResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(HealthAllOkResponse* other); + void InternalSwap(GpsInfo* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.HealthAllOkResponse"; + return "mavsdk.rpc.telemetry.GpsInfo"; } protected: - explicit HealthAllOkResponse(::google::protobuf::Arena* arena); - HealthAllOkResponse(::google::protobuf::Arena* arena, const HealthAllOkResponse& from); + explicit GpsInfo(::google::protobuf::Arena* arena); + GpsInfo(::google::protobuf::Arena* arena, const GpsInfo& from); public: static const ClassData _class_data_; @@ -13578,25 +13728,36 @@ class HealthAllOkResponse final : // accessors ------------------------------------------------------- enum : int { - kIsHealthAllOkFieldNumber = 1, + kNumSatellitesFieldNumber = 1, + kFixTypeFieldNumber = 2, }; - // bool is_health_all_ok = 1; - void clear_is_health_all_ok() ; - bool is_health_all_ok() const; - void set_is_health_all_ok(bool value); + // int32 num_satellites = 1 [(.mavsdk.options.default_value) = "0"]; + void clear_num_satellites() ; + ::int32_t num_satellites() const; + void set_num_satellites(::int32_t value); private: - bool _internal_is_health_all_ok() const; - void _internal_set_is_health_all_ok(bool value); + ::int32_t _internal_num_satellites() const; + void _internal_set_num_satellites(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HealthAllOkResponse) + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + void clear_fix_type() ; + ::mavsdk::rpc::telemetry::FixType fix_type() const; + void set_fix_type(::mavsdk::rpc::telemetry::FixType value); + + private: + ::mavsdk::rpc::telemetry::FixType _internal_fix_type() const; + void _internal_set_fix_type(::mavsdk::rpc::telemetry::FixType value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfo) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -13613,7 +13774,8 @@ class HealthAllOkResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool is_health_all_ok_; + ::int32_t num_satellites_; + int fix_type_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -13621,26 +13783,26 @@ class HealthAllOkResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Health final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Health) */ { +class GpsGlobalOrigin final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsGlobalOrigin) */ { public: - inline Health() : Health(nullptr) {} - ~Health() override; + inline GpsGlobalOrigin() : GpsGlobalOrigin(nullptr) {} + ~GpsGlobalOrigin() override; template - explicit PROTOBUF_CONSTEXPR Health(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GpsGlobalOrigin(::google::protobuf::internal::ConstantInitialized); - inline Health(const Health& from) - : Health(nullptr, from) {} - Health(Health&& from) noexcept - : Health() { + inline GpsGlobalOrigin(const GpsGlobalOrigin& from) + : GpsGlobalOrigin(nullptr, from) {} + GpsGlobalOrigin(GpsGlobalOrigin&& from) noexcept + : GpsGlobalOrigin() { *this = ::std::move(from); } - inline Health& operator=(const Health& from) { + inline GpsGlobalOrigin& operator=(const GpsGlobalOrigin& from) { CopyFrom(from); return *this; } - inline Health& operator=(Health&& from) noexcept { + inline GpsGlobalOrigin& operator=(GpsGlobalOrigin&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -13672,20 +13834,20 @@ class Health final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Health& default_instance() { + static const GpsGlobalOrigin& default_instance() { return *internal_default_instance(); } - static inline const Health* internal_default_instance() { - return reinterpret_cast( - &_Health_default_instance_); + static inline const GpsGlobalOrigin* internal_default_instance() { + return reinterpret_cast( + &_GpsGlobalOrigin_default_instance_); } static constexpr int kIndexInFileMessages = - 131; + 143; - friend void swap(Health& a, Health& b) { + friend void swap(GpsGlobalOrigin& a, GpsGlobalOrigin& b) { a.Swap(&b); } - inline void Swap(Health* other) { + inline void Swap(GpsGlobalOrigin* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -13698,7 +13860,7 @@ class Health final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Health* other) { + void UnsafeArenaSwap(GpsGlobalOrigin* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -13706,14 +13868,14 @@ class Health final : // implements Message ---------------------------------------------- - Health* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GpsGlobalOrigin* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Health& from); + void CopyFrom(const GpsGlobalOrigin& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Health& from) { - Health::MergeImpl(*this, from); + void MergeFrom( const GpsGlobalOrigin& from) { + GpsGlobalOrigin::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -13731,16 +13893,16 @@ class Health final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Health* other); + void InternalSwap(GpsGlobalOrigin* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Health"; + return "mavsdk.rpc.telemetry.GpsGlobalOrigin"; } protected: - explicit Health(::google::protobuf::Arena* arena); - Health(::google::protobuf::Arena* arena, const Health& from); + explicit GpsGlobalOrigin(::google::protobuf::Arena* arena); + GpsGlobalOrigin(::google::protobuf::Arena* arena, const GpsGlobalOrigin& from); public: static const ClassData _class_data_; @@ -13753,91 +13915,47 @@ class Health final : // accessors ------------------------------------------------------- enum : int { - kIsGyrometerCalibrationOkFieldNumber = 1, - kIsAccelerometerCalibrationOkFieldNumber = 2, - kIsMagnetometerCalibrationOkFieldNumber = 3, - kIsLocalPositionOkFieldNumber = 5, - kIsGlobalPositionOkFieldNumber = 6, - kIsHomePositionOkFieldNumber = 7, - kIsArmableFieldNumber = 8, + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAltitudeMFieldNumber = 3, }; - // bool is_gyrometer_calibration_ok = 1 [(.mavsdk.options.default_value) = "false"]; - void clear_is_gyrometer_calibration_ok() ; - bool is_gyrometer_calibration_ok() const; - void set_is_gyrometer_calibration_ok(bool value); - - private: - bool _internal_is_gyrometer_calibration_ok() const; - void _internal_set_is_gyrometer_calibration_ok(bool value); - - public: - // bool is_accelerometer_calibration_ok = 2 [(.mavsdk.options.default_value) = "false"]; - void clear_is_accelerometer_calibration_ok() ; - bool is_accelerometer_calibration_ok() const; - void set_is_accelerometer_calibration_ok(bool value); - - private: - bool _internal_is_accelerometer_calibration_ok() const; - void _internal_set_is_accelerometer_calibration_ok(bool value); - - public: - // bool is_magnetometer_calibration_ok = 3 [(.mavsdk.options.default_value) = "false"]; - void clear_is_magnetometer_calibration_ok() ; - bool is_magnetometer_calibration_ok() const; - void set_is_magnetometer_calibration_ok(bool value); - - private: - bool _internal_is_magnetometer_calibration_ok() const; - void _internal_set_is_magnetometer_calibration_ok(bool value); - - public: - // bool is_local_position_ok = 5 [(.mavsdk.options.default_value) = "false"]; - void clear_is_local_position_ok() ; - bool is_local_position_ok() const; - void set_is_local_position_ok(bool value); - - private: - bool _internal_is_local_position_ok() const; - void _internal_set_is_local_position_ok(bool value); - - public: - // bool is_global_position_ok = 6 [(.mavsdk.options.default_value) = "false"]; - void clear_is_global_position_ok() ; - bool is_global_position_ok() const; - void set_is_global_position_ok(bool value); + // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_latitude_deg() ; + double latitude_deg() const; + void set_latitude_deg(double value); private: - bool _internal_is_global_position_ok() const; - void _internal_set_is_global_position_ok(bool value); + double _internal_latitude_deg() const; + void _internal_set_latitude_deg(double value); public: - // bool is_home_position_ok = 7 [(.mavsdk.options.default_value) = "false"]; - void clear_is_home_position_ok() ; - bool is_home_position_ok() const; - void set_is_home_position_ok(bool value); + // double longitude_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); private: - bool _internal_is_home_position_ok() const; - void _internal_set_is_home_position_ok(bool value); + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); public: - // bool is_armable = 8 [(.mavsdk.options.default_value) = "false"]; - void clear_is_armable() ; - bool is_armable() const; - void set_is_armable(bool value); + // float altitude_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_m() ; + float altitude_m() const; + void set_altitude_m(float value); private: - bool _internal_is_armable() const; - void _internal_set_is_armable(bool value); + float _internal_altitude_m() const; + void _internal_set_altitude_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsGlobalOrigin) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 7, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -13854,13 +13972,9 @@ class Health final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool is_gyrometer_calibration_ok_; - bool is_accelerometer_calibration_ok_; - bool is_magnetometer_calibration_ok_; - bool is_local_position_ok_; - bool is_global_position_ok_; - bool is_home_position_ok_; - bool is_armable_; + double latitude_deg_; + double longitude_deg_; + float altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -13868,26 +13982,25 @@ class Health final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Heading final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Heading) */ { +class GetGpsGlobalOriginRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest) */ { public: - inline Heading() : Heading(nullptr) {} - ~Heading() override; + inline GetGpsGlobalOriginRequest() : GetGpsGlobalOriginRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR Heading(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginRequest(::google::protobuf::internal::ConstantInitialized); - inline Heading(const Heading& from) - : Heading(nullptr, from) {} - Heading(Heading&& from) noexcept - : Heading() { + inline GetGpsGlobalOriginRequest(const GetGpsGlobalOriginRequest& from) + : GetGpsGlobalOriginRequest(nullptr, from) {} + GetGpsGlobalOriginRequest(GetGpsGlobalOriginRequest&& from) noexcept + : GetGpsGlobalOriginRequest() { *this = ::std::move(from); } - inline Heading& operator=(const Heading& from) { + inline GetGpsGlobalOriginRequest& operator=(const GetGpsGlobalOriginRequest& from) { CopyFrom(from); return *this; } - inline Heading& operator=(Heading&& from) noexcept { + inline GetGpsGlobalOriginRequest& operator=(GetGpsGlobalOriginRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -13919,20 +14032,20 @@ class Heading final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Heading& default_instance() { + static const GetGpsGlobalOriginRequest& default_instance() { return *internal_default_instance(); } - static inline const Heading* internal_default_instance() { - return reinterpret_cast( - &_Heading_default_instance_); + static inline const GetGpsGlobalOriginRequest* internal_default_instance() { + return reinterpret_cast( + &_GetGpsGlobalOriginRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 124; + 111; - friend void swap(Heading& a, Heading& b) { + friend void swap(GetGpsGlobalOriginRequest& a, GetGpsGlobalOriginRequest& b) { a.Swap(&b); } - inline void Swap(Heading* other) { + inline void Swap(GetGpsGlobalOriginRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -13945,7 +14058,7 @@ class Heading final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Heading* other) { + void UnsafeArenaSwap(GetGpsGlobalOriginRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -13953,74 +14066,39 @@ class Heading final : // implements Message ---------------------------------------------- - Heading* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GetGpsGlobalOriginRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Heading& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Heading& from) { - Heading::MergeImpl(*this, from); + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const GetGpsGlobalOriginRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const GetGpsGlobalOriginRequest& 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(Heading* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Heading"; + return "mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest"; } protected: - explicit Heading(::google::protobuf::Arena* arena); - Heading(::google::protobuf::Arena* arena, const Heading& from); + explicit GetGpsGlobalOriginRequest(::google::protobuf::Arena* arena); + GetGpsGlobalOriginRequest(::google::protobuf::Arena* arena, const GetGpsGlobalOriginRequest& 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 { - kHeadingDegFieldNumber = 1, - }; - // double heading_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_heading_deg() ; - double heading_deg() const; - void set_heading_deg(double value); - - private: - double _internal_heading_deg() const; - void _internal_set_heading_deg(double value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Heading) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest) 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 @@ -14035,34 +14113,31 @@ class Heading final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - double heading_deg_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; - union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GroundTruth final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GroundTruth) */ { +class FlightModeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FlightModeResponse) */ { public: - inline GroundTruth() : GroundTruth(nullptr) {} - ~GroundTruth() override; + inline FlightModeResponse() : FlightModeResponse(nullptr) {} + ~FlightModeResponse() override; template - explicit PROTOBUF_CONSTEXPR GroundTruth(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FlightModeResponse(::google::protobuf::internal::ConstantInitialized); - inline GroundTruth(const GroundTruth& from) - : GroundTruth(nullptr, from) {} - GroundTruth(GroundTruth&& from) noexcept - : GroundTruth() { + inline FlightModeResponse(const FlightModeResponse& from) + : FlightModeResponse(nullptr, from) {} + FlightModeResponse(FlightModeResponse&& from) noexcept + : FlightModeResponse() { *this = ::std::move(from); } - inline GroundTruth& operator=(const GroundTruth& from) { + inline FlightModeResponse& operator=(const FlightModeResponse& from) { CopyFrom(from); return *this; } - inline GroundTruth& operator=(GroundTruth&& from) noexcept { + inline FlightModeResponse& operator=(FlightModeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14094,20 +14169,20 @@ class GroundTruth final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GroundTruth& default_instance() { + static const FlightModeResponse& default_instance() { return *internal_default_instance(); } - static inline const GroundTruth* internal_default_instance() { - return reinterpret_cast( - &_GroundTruth_default_instance_); + static inline const FlightModeResponse* internal_default_instance() { + return reinterpret_cast( + &_FlightModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 145; + 27; - friend void swap(GroundTruth& a, GroundTruth& b) { + friend void swap(FlightModeResponse& a, FlightModeResponse& b) { a.Swap(&b); } - inline void Swap(GroundTruth* other) { + inline void Swap(FlightModeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -14120,7 +14195,7 @@ class GroundTruth final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GroundTruth* other) { + void UnsafeArenaSwap(FlightModeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -14128,14 +14203,14 @@ class GroundTruth final : // implements Message ---------------------------------------------- - GroundTruth* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FlightModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GroundTruth& from); + void CopyFrom(const FlightModeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GroundTruth& from) { - GroundTruth::MergeImpl(*this, from); + void MergeFrom( const FlightModeResponse& from) { + FlightModeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -14153,16 +14228,16 @@ class GroundTruth final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GroundTruth* other); + void InternalSwap(FlightModeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GroundTruth"; + return "mavsdk.rpc.telemetry.FlightModeResponse"; } protected: - explicit GroundTruth(::google::protobuf::Arena* arena); - GroundTruth(::google::protobuf::Arena* arena, const GroundTruth& from); + explicit FlightModeResponse(::google::protobuf::Arena* arena); + FlightModeResponse(::google::protobuf::Arena* arena, const FlightModeResponse& from); public: static const ClassData _class_data_; @@ -14175,47 +14250,25 @@ class GroundTruth final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAbsoluteAltitudeMFieldNumber = 3, + kFlightModeFieldNumber = 1, }; - // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - 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 [(.mavsdk.options.default_value) = "NaN"]; - 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 [(.mavsdk.options.default_value) = "NaN"]; - void clear_absolute_altitude_m() ; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + void clear_flight_mode() ; + ::mavsdk::rpc::telemetry::FlightMode flight_mode() const; + void set_flight_mode(::mavsdk::rpc::telemetry::FlightMode value); private: - float _internal_absolute_altitude_m() const; - void _internal_set_absolute_altitude_m(float value); + ::mavsdk::rpc::telemetry::FlightMode _internal_flight_mode() const; + void _internal_set_flight_mode(::mavsdk::rpc::telemetry::FlightMode value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GroundTruth) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FlightModeResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -14232,9 +14285,7 @@ class GroundTruth 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_; + int flight_mode_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -14242,26 +14293,26 @@ class GroundTruth final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GpsInfo final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfo) */ { +class FixedwingMetrics final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FixedwingMetrics) */ { public: - inline GpsInfo() : GpsInfo(nullptr) {} - ~GpsInfo() override; + inline FixedwingMetrics() : FixedwingMetrics(nullptr) {} + ~FixedwingMetrics() override; template - explicit PROTOBUF_CONSTEXPR GpsInfo(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FixedwingMetrics(::google::protobuf::internal::ConstantInitialized); - inline GpsInfo(const GpsInfo& from) - : GpsInfo(nullptr, from) {} - GpsInfo(GpsInfo&& from) noexcept - : GpsInfo() { + inline FixedwingMetrics(const FixedwingMetrics& from) + : FixedwingMetrics(nullptr, from) {} + FixedwingMetrics(FixedwingMetrics&& from) noexcept + : FixedwingMetrics() { *this = ::std::move(from); } - inline GpsInfo& operator=(const GpsInfo& from) { + inline FixedwingMetrics& operator=(const FixedwingMetrics& from) { CopyFrom(from); return *this; } - inline GpsInfo& operator=(GpsInfo&& from) noexcept { + inline FixedwingMetrics& operator=(FixedwingMetrics&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14293,20 +14344,20 @@ class GpsInfo final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GpsInfo& default_instance() { + static const FixedwingMetrics& default_instance() { return *internal_default_instance(); } - static inline const GpsInfo* internal_default_instance() { - return reinterpret_cast( - &_GpsInfo_default_instance_); + static inline const FixedwingMetrics* internal_default_instance() { + return reinterpret_cast( + &_FixedwingMetrics_default_instance_); } static constexpr int kIndexInFileMessages = - 128; + 138; - friend void swap(GpsInfo& a, GpsInfo& b) { + friend void swap(FixedwingMetrics& a, FixedwingMetrics& b) { a.Swap(&b); } - inline void Swap(GpsInfo* other) { + inline void Swap(FixedwingMetrics* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -14319,7 +14370,7 @@ class GpsInfo final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GpsInfo* other) { + void UnsafeArenaSwap(FixedwingMetrics* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -14327,14 +14378,14 @@ class GpsInfo final : // implements Message ---------------------------------------------- - GpsInfo* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FixedwingMetrics* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GpsInfo& from); + void CopyFrom(const FixedwingMetrics& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GpsInfo& from) { - GpsInfo::MergeImpl(*this, from); + void MergeFrom( const FixedwingMetrics& from) { + FixedwingMetrics::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -14352,16 +14403,16 @@ class GpsInfo final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GpsInfo* other); + void InternalSwap(FixedwingMetrics* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GpsInfo"; + return "mavsdk.rpc.telemetry.FixedwingMetrics"; } protected: - explicit GpsInfo(::google::protobuf::Arena* arena); - GpsInfo(::google::protobuf::Arena* arena, const GpsInfo& from); + explicit FixedwingMetrics(::google::protobuf::Arena* arena); + FixedwingMetrics(::google::protobuf::Arena* arena, const FixedwingMetrics& from); public: static const ClassData _class_data_; @@ -14374,36 +14425,47 @@ class GpsInfo final : // accessors ------------------------------------------------------- enum : int { - kNumSatellitesFieldNumber = 1, - kFixTypeFieldNumber = 2, + kAirspeedMSFieldNumber = 1, + kThrottlePercentageFieldNumber = 2, + kClimbRateMSFieldNumber = 3, }; - // int32 num_satellites = 1 [(.mavsdk.options.default_value) = "0"]; - void clear_num_satellites() ; - ::int32_t num_satellites() const; - void set_num_satellites(::int32_t value); + // float airspeed_m_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_airspeed_m_s() ; + float airspeed_m_s() const; + void set_airspeed_m_s(float value); private: - ::int32_t _internal_num_satellites() const; - void _internal_set_num_satellites(::int32_t value); + float _internal_airspeed_m_s() const; + void _internal_set_airspeed_m_s(float value); public: - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - void clear_fix_type() ; - ::mavsdk::rpc::telemetry::FixType fix_type() const; - void set_fix_type(::mavsdk::rpc::telemetry::FixType value); + // float throttle_percentage = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_throttle_percentage() ; + float throttle_percentage() const; + void set_throttle_percentage(float value); private: - ::mavsdk::rpc::telemetry::FixType _internal_fix_type() const; - void _internal_set_fix_type(::mavsdk::rpc::telemetry::FixType value); + float _internal_throttle_percentage() const; + void _internal_set_throttle_percentage(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfo) + // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_climb_rate_m_s() ; + float climb_rate_m_s() const; + void set_climb_rate_m_s(float value); + + private: + float _internal_climb_rate_m_s() const; + void _internal_set_climb_rate_m_s(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FixedwingMetrics) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -14420,8 +14482,9 @@ class GpsInfo final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::int32_t num_satellites_; - int fix_type_; + float airspeed_m_s_; + float throttle_percentage_; + float climb_rate_m_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -14429,26 +14492,26 @@ class GpsInfo final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GpsGlobalOrigin final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsGlobalOrigin) */ { +class EulerAngle final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.EulerAngle) */ { public: - inline GpsGlobalOrigin() : GpsGlobalOrigin(nullptr) {} - ~GpsGlobalOrigin() override; + inline EulerAngle() : EulerAngle(nullptr) {} + ~EulerAngle() override; template - explicit PROTOBUF_CONSTEXPR GpsGlobalOrigin(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR EulerAngle(::google::protobuf::internal::ConstantInitialized); - inline GpsGlobalOrigin(const GpsGlobalOrigin& from) - : GpsGlobalOrigin(nullptr, from) {} - GpsGlobalOrigin(GpsGlobalOrigin&& from) noexcept - : GpsGlobalOrigin() { + inline EulerAngle(const EulerAngle& from) + : EulerAngle(nullptr, from) {} + EulerAngle(EulerAngle&& from) noexcept + : EulerAngle() { *this = ::std::move(from); } - inline GpsGlobalOrigin& operator=(const GpsGlobalOrigin& from) { + inline EulerAngle& operator=(const EulerAngle& from) { CopyFrom(from); return *this; } - inline GpsGlobalOrigin& operator=(GpsGlobalOrigin&& from) noexcept { + inline EulerAngle& operator=(EulerAngle&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14480,20 +14543,20 @@ class GpsGlobalOrigin final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GpsGlobalOrigin& default_instance() { + static const EulerAngle& default_instance() { return *internal_default_instance(); } - static inline const GpsGlobalOrigin* internal_default_instance() { - return reinterpret_cast( - &_GpsGlobalOrigin_default_instance_); + static inline const EulerAngle* internal_default_instance() { + return reinterpret_cast( + &_EulerAngle_default_instance_); } static constexpr int kIndexInFileMessages = - 151; + 118; - friend void swap(GpsGlobalOrigin& a, GpsGlobalOrigin& b) { + friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); } - inline void Swap(GpsGlobalOrigin* other) { + inline void Swap(EulerAngle* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -14506,7 +14569,7 @@ class GpsGlobalOrigin final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GpsGlobalOrigin* other) { + void UnsafeArenaSwap(EulerAngle* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -14514,14 +14577,14 @@ class GpsGlobalOrigin final : // implements Message ---------------------------------------------- - GpsGlobalOrigin* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + EulerAngle* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GpsGlobalOrigin& from); + void CopyFrom(const EulerAngle& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GpsGlobalOrigin& from) { - GpsGlobalOrigin::MergeImpl(*this, from); + void MergeFrom( const EulerAngle& from) { + EulerAngle::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -14539,16 +14602,16 @@ class GpsGlobalOrigin final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GpsGlobalOrigin* other); + void InternalSwap(EulerAngle* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GpsGlobalOrigin"; + return "mavsdk.rpc.telemetry.EulerAngle"; } protected: - explicit GpsGlobalOrigin(::google::protobuf::Arena* arena); - GpsGlobalOrigin(::google::protobuf::Arena* arena, const GpsGlobalOrigin& from); + explicit EulerAngle(::google::protobuf::Arena* arena); + EulerAngle(::google::protobuf::Arena* arena, const EulerAngle& from); public: static const ClassData _class_data_; @@ -14561,47 +14624,58 @@ class GpsGlobalOrigin final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAltitudeMFieldNumber = 3, + kRollDegFieldNumber = 1, + kPitchDegFieldNumber = 2, + kTimestampUsFieldNumber = 4, + kYawDegFieldNumber = 3, }; - // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_latitude_deg() ; - double latitude_deg() const; - void set_latitude_deg(double value); + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_roll_deg() ; + float roll_deg() const; + void set_roll_deg(float value); private: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); + float _internal_roll_deg() const; + void _internal_set_roll_deg(float value); public: - // double longitude_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_pitch_deg() ; + float pitch_deg() const; + void set_pitch_deg(float value); private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); + float _internal_pitch_deg() const; + void _internal_set_pitch_deg(float value); public: - // float altitude_m = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_m() ; - float altitude_m() const; - void set_altitude_m(float value); + // uint64 timestamp_us = 4; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); private: - float _internal_altitude_m() const; - void _internal_set_altitude_m(float value); + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsGlobalOrigin) + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_yaw_deg() ; + float yaw_deg() const; + void set_yaw_deg(float value); + + private: + float _internal_yaw_deg() const; + void _internal_set_yaw_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.EulerAngle) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -14618,9 +14692,10 @@ class GpsGlobalOrigin 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 altitude_m_; + float roll_deg_; + float pitch_deg_; + ::uint64_t timestamp_us_; + float yaw_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -14628,25 +14703,26 @@ class GpsGlobalOrigin final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GetGpsGlobalOriginRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest) */ { +class Covariance final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Covariance) */ { public: - inline GetGpsGlobalOriginRequest() : GetGpsGlobalOriginRequest(nullptr) {} + inline Covariance() : Covariance(nullptr) {} + ~Covariance() override; template - explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Covariance(::google::protobuf::internal::ConstantInitialized); - inline GetGpsGlobalOriginRequest(const GetGpsGlobalOriginRequest& from) - : GetGpsGlobalOriginRequest(nullptr, from) {} - GetGpsGlobalOriginRequest(GetGpsGlobalOriginRequest&& from) noexcept - : GetGpsGlobalOriginRequest() { + inline Covariance(const Covariance& from) + : Covariance(nullptr, from) {} + Covariance(Covariance&& from) noexcept + : Covariance() { *this = ::std::move(from); } - inline GetGpsGlobalOriginRequest& operator=(const GetGpsGlobalOriginRequest& from) { + inline Covariance& operator=(const Covariance& from) { CopyFrom(from); return *this; } - inline GetGpsGlobalOriginRequest& operator=(GetGpsGlobalOriginRequest&& from) noexcept { + inline Covariance& operator=(Covariance&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14678,20 +14754,20 @@ class GetGpsGlobalOriginRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GetGpsGlobalOriginRequest& default_instance() { + static const Covariance& default_instance() { return *internal_default_instance(); } - static inline const GetGpsGlobalOriginRequest* internal_default_instance() { - return reinterpret_cast( - &_GetGpsGlobalOriginRequest_default_instance_); + static inline const Covariance* internal_default_instance() { + return reinterpret_cast( + &_Covariance_default_instance_); } static constexpr int kIndexInFileMessages = - 119; + 128; - friend void swap(GetGpsGlobalOriginRequest& a, GetGpsGlobalOriginRequest& b) { + friend void swap(Covariance& a, Covariance& b) { a.Swap(&b); } - inline void Swap(GetGpsGlobalOriginRequest* other) { + inline void Swap(Covariance* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -14704,7 +14780,7 @@ class GetGpsGlobalOriginRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GetGpsGlobalOriginRequest* other) { + void UnsafeArenaSwap(Covariance* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -14712,45 +14788,88 @@ class GetGpsGlobalOriginRequest final : // implements Message ---------------------------------------------- - GetGpsGlobalOriginRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const GetGpsGlobalOriginRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + Covariance* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const GetGpsGlobalOriginRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const Covariance& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const Covariance& from) { + Covariance::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(Covariance* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GetGpsGlobalOriginRequest"; + return "mavsdk.rpc.telemetry.Covariance"; } protected: - explicit GetGpsGlobalOriginRequest(::google::protobuf::Arena* arena); - GetGpsGlobalOriginRequest(::google::protobuf::Arena* arena, const GetGpsGlobalOriginRequest& from); + explicit Covariance(::google::protobuf::Arena* arena); + Covariance(::google::protobuf::Arena* arena, const Covariance& 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.telemetry.GetGpsGlobalOriginRequest) - private: - class _Internal; + enum : int { + kCovarianceMatrixFieldNumber = 1, + }; + // repeated float covariance_matrix = 1; + int covariance_matrix_size() const; + private: + int _internal_covariance_matrix_size() const; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; + public: + void clear_covariance_matrix() ; + float covariance_matrix(int index) const; + void set_covariance_matrix(int index, float value); + void add_covariance_matrix(float value); + const ::google::protobuf::RepeatedField& covariance_matrix() const; + ::google::protobuf::RepeatedField* mutable_covariance_matrix(); + + private: + const ::google::protobuf::RepeatedField& _internal_covariance_matrix() const; + ::google::protobuf::RepeatedField* _internal_mutable_covariance_matrix(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Covariance) + 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 + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; struct Impl_ { inline explicit constexpr Impl_( @@ -14759,31 +14878,34 @@ class GetGpsGlobalOriginRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::RepeatedField covariance_matrix_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class FlightModeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FlightModeResponse) */ { +class Battery final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Battery) */ { public: - inline FlightModeResponse() : FlightModeResponse(nullptr) {} - ~FlightModeResponse() override; + inline Battery() : Battery(nullptr) {} + ~Battery() override; template - explicit PROTOBUF_CONSTEXPR FlightModeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Battery(::google::protobuf::internal::ConstantInitialized); - inline FlightModeResponse(const FlightModeResponse& from) - : FlightModeResponse(nullptr, from) {} - FlightModeResponse(FlightModeResponse&& from) noexcept - : FlightModeResponse() { + inline Battery(const Battery& from) + : Battery(nullptr, from) {} + Battery(Battery&& from) noexcept + : Battery() { *this = ::std::move(from); } - inline FlightModeResponse& operator=(const FlightModeResponse& from) { + inline Battery& operator=(const Battery& from) { CopyFrom(from); return *this; } - inline FlightModeResponse& operator=(FlightModeResponse&& from) noexcept { + inline Battery& operator=(Battery&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14815,20 +14937,20 @@ class FlightModeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FlightModeResponse& default_instance() { + static const Battery& default_instance() { return *internal_default_instance(); } - static inline const FlightModeResponse* internal_default_instance() { - return reinterpret_cast( - &_FlightModeResponse_default_instance_); + static inline const Battery* internal_default_instance() { + return reinterpret_cast( + &_Battery_default_instance_); } static constexpr int kIndexInFileMessages = - 31; + 122; - friend void swap(FlightModeResponse& a, FlightModeResponse& b) { + friend void swap(Battery& a, Battery& b) { a.Swap(&b); } - inline void Swap(FlightModeResponse* other) { + inline void Swap(Battery* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -14841,7 +14963,7 @@ class FlightModeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FlightModeResponse* other) { + void UnsafeArenaSwap(Battery* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -14849,14 +14971,14 @@ class FlightModeResponse final : // implements Message ---------------------------------------------- - FlightModeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Battery* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FlightModeResponse& from); + void CopyFrom(const Battery& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FlightModeResponse& from) { - FlightModeResponse::MergeImpl(*this, from); + void MergeFrom( const Battery& from) { + Battery::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -14874,16 +14996,16 @@ class FlightModeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(FlightModeResponse* other); + void InternalSwap(Battery* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.FlightModeResponse"; + return "mavsdk.rpc.telemetry.Battery"; } protected: - explicit FlightModeResponse(::google::protobuf::Arena* arena); - FlightModeResponse(::google::protobuf::Arena* arena, const FlightModeResponse& from); + explicit Battery(::google::protobuf::Arena* arena); + Battery(::google::protobuf::Arena* arena, const Battery& from); public: static const ClassData _class_data_; @@ -14896,25 +15018,80 @@ class FlightModeResponse final : // accessors ------------------------------------------------------- enum : int { - kFlightModeFieldNumber = 1, + kIdFieldNumber = 1, + kTemperatureDegcFieldNumber = 2, + kVoltageVFieldNumber = 3, + kCurrentBatteryAFieldNumber = 4, + kCapacityConsumedAhFieldNumber = 5, + kRemainingPercentFieldNumber = 6, }; - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - void clear_flight_mode() ; - ::mavsdk::rpc::telemetry::FlightMode flight_mode() const; - void set_flight_mode(::mavsdk::rpc::telemetry::FlightMode value); + // uint32 id = 1 [(.mavsdk.options.default_value) = "0"]; + void clear_id() ; + ::uint32_t id() const; + void set_id(::uint32_t value); private: - ::mavsdk::rpc::telemetry::FlightMode _internal_flight_mode() const; - void _internal_set_flight_mode(::mavsdk::rpc::telemetry::FlightMode value); + ::uint32_t _internal_id() const; + void _internal_set_id(::uint32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FlightModeResponse) + // float temperature_degc = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_temperature_degc() ; + float temperature_degc() const; + void set_temperature_degc(float value); + + private: + float _internal_temperature_degc() const; + void _internal_set_temperature_degc(float value); + + public: + // float voltage_v = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_voltage_v() ; + float voltage_v() const; + void set_voltage_v(float value); + + private: + float _internal_voltage_v() const; + void _internal_set_voltage_v(float value); + + public: + // float current_battery_a = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_current_battery_a() ; + float current_battery_a() const; + void set_current_battery_a(float value); + + private: + float _internal_current_battery_a() const; + void _internal_set_current_battery_a(float value); + + public: + // float capacity_consumed_ah = 5 [(.mavsdk.options.default_value) = "NaN"]; + void clear_capacity_consumed_ah() ; + float capacity_consumed_ah() const; + void set_capacity_consumed_ah(float value); + + private: + float _internal_capacity_consumed_ah() const; + void _internal_set_capacity_consumed_ah(float value); + + public: + // float remaining_percent = 6 [(.mavsdk.options.default_value) = "NaN"]; + void clear_remaining_percent() ; + float remaining_percent() const; + void set_remaining_percent(float value); + + private: + float _internal_remaining_percent() const; + void _internal_set_remaining_percent(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Battery) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 3, 6, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -14931,7 +15108,12 @@ class FlightModeResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int flight_mode_; + ::uint32_t id_; + float temperature_degc_; + float voltage_v_; + float current_battery_a_; + float capacity_consumed_ah_; + float remaining_percent_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -14939,26 +15121,26 @@ class FlightModeResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class FixedwingMetrics final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FixedwingMetrics) */ { +class ArmedResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ArmedResponse) */ { public: - inline FixedwingMetrics() : FixedwingMetrics(nullptr) {} - ~FixedwingMetrics() override; + inline ArmedResponse() : ArmedResponse(nullptr) {} + ~ArmedResponse() override; template - explicit PROTOBUF_CONSTEXPR FixedwingMetrics(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ArmedResponse(::google::protobuf::internal::ConstantInitialized); - inline FixedwingMetrics(const FixedwingMetrics& from) - : FixedwingMetrics(nullptr, from) {} - FixedwingMetrics(FixedwingMetrics&& from) noexcept - : FixedwingMetrics() { + inline ArmedResponse(const ArmedResponse& from) + : ArmedResponse(nullptr, from) {} + ArmedResponse(ArmedResponse&& from) noexcept + : ArmedResponse() { *this = ::std::move(from); } - inline FixedwingMetrics& operator=(const FixedwingMetrics& from) { + inline ArmedResponse& operator=(const ArmedResponse& from) { CopyFrom(from); return *this; } - inline FixedwingMetrics& operator=(FixedwingMetrics&& from) noexcept { + inline ArmedResponse& operator=(ArmedResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -14990,20 +15172,20 @@ class FixedwingMetrics final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FixedwingMetrics& default_instance() { + static const ArmedResponse& default_instance() { return *internal_default_instance(); } - static inline const FixedwingMetrics* internal_default_instance() { - return reinterpret_cast( - &_FixedwingMetrics_default_instance_); + static inline const ArmedResponse* internal_default_instance() { + return reinterpret_cast( + &_ArmedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 146; + 9; - friend void swap(FixedwingMetrics& a, FixedwingMetrics& b) { + friend void swap(ArmedResponse& a, ArmedResponse& b) { a.Swap(&b); } - inline void Swap(FixedwingMetrics* other) { + inline void Swap(ArmedResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -15016,7 +15198,7 @@ class FixedwingMetrics final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FixedwingMetrics* other) { + void UnsafeArenaSwap(ArmedResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -15024,14 +15206,14 @@ class FixedwingMetrics final : // implements Message ---------------------------------------------- - FixedwingMetrics* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ArmedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FixedwingMetrics& from); + void CopyFrom(const ArmedResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FixedwingMetrics& from) { - FixedwingMetrics::MergeImpl(*this, from); + void MergeFrom( const ArmedResponse& from) { + ArmedResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -15049,16 +15231,16 @@ class FixedwingMetrics final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(FixedwingMetrics* other); + void InternalSwap(ArmedResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.FixedwingMetrics"; + return "mavsdk.rpc.telemetry.ArmedResponse"; } protected: - explicit FixedwingMetrics(::google::protobuf::Arena* arena); - FixedwingMetrics(::google::protobuf::Arena* arena, const FixedwingMetrics& from); + explicit ArmedResponse(::google::protobuf::Arena* arena); + ArmedResponse(::google::protobuf::Arena* arena, const ArmedResponse& from); public: static const ClassData _class_data_; @@ -15071,47 +15253,25 @@ class FixedwingMetrics final : // accessors ------------------------------------------------------- enum : int { - kAirspeedMSFieldNumber = 1, - kThrottlePercentageFieldNumber = 2, - kClimbRateMSFieldNumber = 3, + kIsArmedFieldNumber = 1, }; - // float airspeed_m_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_airspeed_m_s() ; - float airspeed_m_s() const; - void set_airspeed_m_s(float value); - - private: - float _internal_airspeed_m_s() const; - void _internal_set_airspeed_m_s(float value); - - public: - // float throttle_percentage = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_throttle_percentage() ; - float throttle_percentage() const; - void set_throttle_percentage(float value); + // bool is_armed = 1; + void clear_is_armed() ; + bool is_armed() const; + void set_is_armed(bool value); private: - float _internal_throttle_percentage() const; - void _internal_set_throttle_percentage(float value); + bool _internal_is_armed() const; + void _internal_set_is_armed(bool value); public: - // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_climb_rate_m_s() ; - float climb_rate_m_s() const; - void set_climb_rate_m_s(float value); - - private: - float _internal_climb_rate_m_s() const; - void _internal_set_climb_rate_m_s(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FixedwingMetrics) - private: - class _Internal; + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ArmedResponse) + private: + class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -15128,9 +15288,7 @@ class FixedwingMetrics final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float airspeed_m_s_; - float throttle_percentage_; - float climb_rate_m_s_; + bool is_armed_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15138,26 +15296,26 @@ class FixedwingMetrics final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class EulerAngle final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.EulerAngle) */ { +class AngularVelocityFrd final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AngularVelocityFrd) */ { public: - inline EulerAngle() : EulerAngle(nullptr) {} - ~EulerAngle() override; + inline AngularVelocityFrd() : AngularVelocityFrd(nullptr) {} + ~AngularVelocityFrd() override; template - explicit PROTOBUF_CONSTEXPR EulerAngle(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR AngularVelocityFrd(::google::protobuf::internal::ConstantInitialized); - inline EulerAngle(const EulerAngle& from) - : EulerAngle(nullptr, from) {} - EulerAngle(EulerAngle&& from) noexcept - : EulerAngle() { + inline AngularVelocityFrd(const AngularVelocityFrd& from) + : AngularVelocityFrd(nullptr, from) {} + AngularVelocityFrd(AngularVelocityFrd&& from) noexcept + : AngularVelocityFrd() { *this = ::std::move(from); } - inline EulerAngle& operator=(const EulerAngle& from) { + inline AngularVelocityFrd& operator=(const AngularVelocityFrd& from) { CopyFrom(from); return *this; } - inline EulerAngle& operator=(EulerAngle&& from) noexcept { + inline AngularVelocityFrd& operator=(AngularVelocityFrd&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -15189,20 +15347,20 @@ class EulerAngle final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const EulerAngle& default_instance() { + static const AngularVelocityFrd& default_instance() { return *internal_default_instance(); } - static inline const EulerAngle* internal_default_instance() { - return reinterpret_cast( - &_EulerAngle_default_instance_); + static inline const AngularVelocityFrd* internal_default_instance() { + return reinterpret_cast( + &_AngularVelocityFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 126; + 140; - friend void swap(EulerAngle& a, EulerAngle& b) { + friend void swap(AngularVelocityFrd& a, AngularVelocityFrd& b) { a.Swap(&b); } - inline void Swap(EulerAngle* other) { + inline void Swap(AngularVelocityFrd* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -15215,7 +15373,7 @@ class EulerAngle final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(EulerAngle* other) { + void UnsafeArenaSwap(AngularVelocityFrd* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -15223,14 +15381,14 @@ class EulerAngle final : // implements Message ---------------------------------------------- - EulerAngle* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + AngularVelocityFrd* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const EulerAngle& from); + void CopyFrom(const AngularVelocityFrd& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const EulerAngle& from) { - EulerAngle::MergeImpl(*this, from); + void MergeFrom( const AngularVelocityFrd& from) { + AngularVelocityFrd::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -15248,16 +15406,16 @@ class EulerAngle final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(EulerAngle* other); + void InternalSwap(AngularVelocityFrd* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.EulerAngle"; + return "mavsdk.rpc.telemetry.AngularVelocityFrd"; } protected: - explicit EulerAngle(::google::protobuf::Arena* arena); - EulerAngle(::google::protobuf::Arena* arena, const EulerAngle& from); + explicit AngularVelocityFrd(::google::protobuf::Arena* arena); + AngularVelocityFrd(::google::protobuf::Arena* arena, const AngularVelocityFrd& from); public: static const ClassData _class_data_; @@ -15270,58 +15428,47 @@ class EulerAngle final : // accessors ------------------------------------------------------- enum : int { - kRollDegFieldNumber = 1, - kPitchDegFieldNumber = 2, - kTimestampUsFieldNumber = 4, - kYawDegFieldNumber = 3, + kForwardRadSFieldNumber = 1, + kRightRadSFieldNumber = 2, + kDownRadSFieldNumber = 3, }; - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_roll_deg() ; - float roll_deg() const; - void set_roll_deg(float value); - - private: - float _internal_roll_deg() const; - void _internal_set_roll_deg(float value); - - public: - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_pitch_deg() ; - float pitch_deg() const; - void set_pitch_deg(float value); + // float forward_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_forward_rad_s() ; + float forward_rad_s() const; + void set_forward_rad_s(float value); private: - float _internal_pitch_deg() const; - void _internal_set_pitch_deg(float value); + float _internal_forward_rad_s() const; + void _internal_set_forward_rad_s(float value); public: - // uint64 timestamp_us = 4; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); + // float right_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_right_rad_s() ; + float right_rad_s() const; + void set_right_rad_s(float value); private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); + float _internal_right_rad_s() const; + void _internal_set_right_rad_s(float value); public: - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_yaw_deg() ; - float yaw_deg() const; - void set_yaw_deg(float value); + // float down_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_down_rad_s() ; + float down_rad_s() const; + void set_down_rad_s(float value); private: - float _internal_yaw_deg() const; - void _internal_set_yaw_deg(float value); + float _internal_down_rad_s() const; + void _internal_set_down_rad_s(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AngularVelocityFrd) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -15338,10 +15485,9 @@ class EulerAngle final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float roll_deg_; - float pitch_deg_; - ::uint64_t timestamp_us_; - float yaw_deg_; + float forward_rad_s_; + float right_rad_s_; + float down_rad_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15349,26 +15495,26 @@ class EulerAngle final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Covariance final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Covariance) */ { +class AngularVelocityBody final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AngularVelocityBody) */ { public: - inline Covariance() : Covariance(nullptr) {} - ~Covariance() override; + inline AngularVelocityBody() : AngularVelocityBody(nullptr) {} + ~AngularVelocityBody() override; template - explicit PROTOBUF_CONSTEXPR Covariance(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR AngularVelocityBody(::google::protobuf::internal::ConstantInitialized); - inline Covariance(const Covariance& from) - : Covariance(nullptr, from) {} - Covariance(Covariance&& from) noexcept - : Covariance() { + inline AngularVelocityBody(const AngularVelocityBody& from) + : AngularVelocityBody(nullptr, from) {} + AngularVelocityBody(AngularVelocityBody&& from) noexcept + : AngularVelocityBody() { *this = ::std::move(from); } - inline Covariance& operator=(const Covariance& from) { + inline AngularVelocityBody& operator=(const AngularVelocityBody& from) { CopyFrom(from); return *this; } - inline Covariance& operator=(Covariance&& from) noexcept { + inline AngularVelocityBody& operator=(AngularVelocityBody&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -15400,20 +15546,20 @@ class Covariance final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Covariance& default_instance() { + static const AngularVelocityBody& default_instance() { return *internal_default_instance(); } - static inline const Covariance* internal_default_instance() { - return reinterpret_cast( - &_Covariance_default_instance_); + static inline const AngularVelocityBody* internal_default_instance() { + return reinterpret_cast( + &_AngularVelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 136; + 119; - friend void swap(Covariance& a, Covariance& b) { + friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { a.Swap(&b); } - inline void Swap(Covariance* other) { + inline void Swap(AngularVelocityBody* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -15426,7 +15572,7 @@ class Covariance final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Covariance* other) { + void UnsafeArenaSwap(AngularVelocityBody* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -15434,14 +15580,14 @@ class Covariance final : // implements Message ---------------------------------------------- - Covariance* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + AngularVelocityBody* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Covariance& from); + void CopyFrom(const AngularVelocityBody& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Covariance& from) { - Covariance::MergeImpl(*this, from); + void MergeFrom( const AngularVelocityBody& from) { + AngularVelocityBody::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -15459,16 +15605,16 @@ class Covariance final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Covariance* other); + void InternalSwap(AngularVelocityBody* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Covariance"; + return "mavsdk.rpc.telemetry.AngularVelocityBody"; } protected: - explicit Covariance(::google::protobuf::Arena* arena); - Covariance(::google::protobuf::Arena* arena, const Covariance& from); + explicit AngularVelocityBody(::google::protobuf::Arena* arena); + AngularVelocityBody(::google::protobuf::Arena* arena, const AngularVelocityBody& from); public: static const ClassData _class_data_; @@ -15481,33 +15627,47 @@ class Covariance final : // accessors ------------------------------------------------------- enum : int { - kCovarianceMatrixFieldNumber = 1, + kRollRadSFieldNumber = 1, + kPitchRadSFieldNumber = 2, + kYawRadSFieldNumber = 3, }; - // repeated float covariance_matrix = 1; - int covariance_matrix_size() const; + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_roll_rad_s() ; + float roll_rad_s() const; + void set_roll_rad_s(float value); + private: - int _internal_covariance_matrix_size() const; + float _internal_roll_rad_s() const; + void _internal_set_roll_rad_s(float value); public: - void clear_covariance_matrix() ; - float covariance_matrix(int index) const; - void set_covariance_matrix(int index, float value); - void add_covariance_matrix(float value); - const ::google::protobuf::RepeatedField& covariance_matrix() const; - ::google::protobuf::RepeatedField* mutable_covariance_matrix(); + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_pitch_rad_s() ; + float pitch_rad_s() const; + void set_pitch_rad_s(float value); private: - const ::google::protobuf::RepeatedField& _internal_covariance_matrix() const; - ::google::protobuf::RepeatedField* _internal_mutable_covariance_matrix(); + float _internal_pitch_rad_s() const; + void _internal_set_pitch_rad_s(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Covariance) + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_yaw_rad_s() ; + float yaw_rad_s() const; + void set_yaw_rad_s(float value); + + private: + float _internal_yaw_rad_s() const; + void _internal_set_yaw_rad_s(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AngularVelocityBody) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -15524,7 +15684,9 @@ class Covariance final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::RepeatedField covariance_matrix_; + float roll_rad_s_; + float pitch_rad_s_; + float yaw_rad_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15532,26 +15694,26 @@ class Covariance final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Battery final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Battery) */ { +class Altitude final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Altitude) */ { public: - inline Battery() : Battery(nullptr) {} - ~Battery() override; + inline Altitude() : Altitude(nullptr) {} + ~Altitude() override; template - explicit PROTOBUF_CONSTEXPR Battery(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Altitude(::google::protobuf::internal::ConstantInitialized); - inline Battery(const Battery& from) - : Battery(nullptr, from) {} - Battery(Battery&& from) noexcept - : Battery() { + inline Altitude(const Altitude& from) + : Altitude(nullptr, from) {} + Altitude(Altitude&& from) noexcept + : Altitude() { *this = ::std::move(from); } - inline Battery& operator=(const Battery& from) { + inline Altitude& operator=(const Altitude& from) { CopyFrom(from); return *this; } - inline Battery& operator=(Battery&& from) noexcept { + inline Altitude& operator=(Altitude&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -15583,20 +15745,20 @@ class Battery final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Battery& default_instance() { + static const Altitude& default_instance() { return *internal_default_instance(); } - static inline const Battery* internal_default_instance() { - return reinterpret_cast( - &_Battery_default_instance_); + static inline const Altitude* internal_default_instance() { + return reinterpret_cast( + &_Altitude_default_instance_); } static constexpr int kIndexInFileMessages = - 130; + 144; - friend void swap(Battery& a, Battery& b) { + friend void swap(Altitude& a, Altitude& b) { a.Swap(&b); } - inline void Swap(Battery* other) { + inline void Swap(Altitude* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -15609,7 +15771,7 @@ class Battery final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Battery* other) { + void UnsafeArenaSwap(Altitude* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -15617,14 +15779,14 @@ class Battery final : // implements Message ---------------------------------------------- - Battery* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Altitude* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Battery& from); + void CopyFrom(const Altitude& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Battery& from) { - Battery::MergeImpl(*this, from); + void MergeFrom( const Altitude& from) { + Altitude::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -15642,16 +15804,16 @@ class Battery final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Battery* other); + void InternalSwap(Altitude* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Battery"; + return "mavsdk.rpc.telemetry.Altitude"; } protected: - explicit Battery(::google::protobuf::Arena* arena); - Battery(::google::protobuf::Arena* arena, const Battery& from); + explicit Altitude(::google::protobuf::Arena* arena); + Altitude(::google::protobuf::Arena* arena, const Altitude& from); public: static const ClassData _class_data_; @@ -15664,74 +15826,74 @@ class Battery final : // accessors ------------------------------------------------------- enum : int { - kIdFieldNumber = 1, - kTemperatureDegcFieldNumber = 2, - kVoltageVFieldNumber = 3, - kCurrentBatteryAFieldNumber = 4, - kCapacityConsumedAhFieldNumber = 5, - kRemainingPercentFieldNumber = 6, + kAltitudeMonotonicMFieldNumber = 1, + kAltitudeAmslMFieldNumber = 2, + kAltitudeLocalMFieldNumber = 3, + kAltitudeRelativeMFieldNumber = 4, + kAltitudeTerrainMFieldNumber = 5, + kBottomClearanceMFieldNumber = 6, }; - // uint32 id = 1 [(.mavsdk.options.default_value) = "0"]; - void clear_id() ; - ::uint32_t id() const; - void set_id(::uint32_t value); + // float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_monotonic_m() ; + float altitude_monotonic_m() const; + void set_altitude_monotonic_m(float value); private: - ::uint32_t _internal_id() const; - void _internal_set_id(::uint32_t value); + float _internal_altitude_monotonic_m() const; + void _internal_set_altitude_monotonic_m(float value); public: - // float temperature_degc = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_temperature_degc() ; - float temperature_degc() const; - void set_temperature_degc(float value); + // float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_amsl_m() ; + float altitude_amsl_m() const; + void set_altitude_amsl_m(float value); private: - float _internal_temperature_degc() const; - void _internal_set_temperature_degc(float value); + float _internal_altitude_amsl_m() const; + void _internal_set_altitude_amsl_m(float value); public: - // float voltage_v = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_voltage_v() ; - float voltage_v() const; - void set_voltage_v(float value); + // float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_local_m() ; + float altitude_local_m() const; + void set_altitude_local_m(float value); private: - float _internal_voltage_v() const; - void _internal_set_voltage_v(float value); + float _internal_altitude_local_m() const; + void _internal_set_altitude_local_m(float value); public: - // float current_battery_a = 4 [(.mavsdk.options.default_value) = "NaN"]; - void clear_current_battery_a() ; - float current_battery_a() const; - void set_current_battery_a(float value); + // float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_relative_m() ; + float altitude_relative_m() const; + void set_altitude_relative_m(float value); private: - float _internal_current_battery_a() const; - void _internal_set_current_battery_a(float value); + float _internal_altitude_relative_m() const; + void _internal_set_altitude_relative_m(float value); public: - // float capacity_consumed_ah = 5 [(.mavsdk.options.default_value) = "NaN"]; - void clear_capacity_consumed_ah() ; - float capacity_consumed_ah() const; - void set_capacity_consumed_ah(float value); + // float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_terrain_m() ; + float altitude_terrain_m() const; + void set_altitude_terrain_m(float value); private: - float _internal_capacity_consumed_ah() const; - void _internal_set_capacity_consumed_ah(float value); + float _internal_altitude_terrain_m() const; + void _internal_set_altitude_terrain_m(float value); public: - // float remaining_percent = 6 [(.mavsdk.options.default_value) = "NaN"]; - void clear_remaining_percent() ; - float remaining_percent() const; - void set_remaining_percent(float value); + // float bottom_clearance_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + void clear_bottom_clearance_m() ; + float bottom_clearance_m() const; + void set_bottom_clearance_m(float value); private: - float _internal_remaining_percent() const; - void _internal_set_remaining_percent(float value); + float _internal_bottom_clearance_m() const; + void _internal_set_bottom_clearance_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Altitude) private: class _Internal; @@ -15754,12 +15916,12 @@ class Battery final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::uint32_t id_; - float temperature_degc_; - float voltage_v_; - float current_battery_a_; - float capacity_consumed_ah_; - float remaining_percent_; + float altitude_monotonic_m_; + float altitude_amsl_m_; + float altitude_local_m_; + float altitude_relative_m_; + float altitude_terrain_m_; + float bottom_clearance_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15767,26 +15929,26 @@ class Battery final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class ArmedResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ArmedResponse) */ { +class ActuatorOutputStatus final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorOutputStatus) */ { public: - inline ArmedResponse() : ArmedResponse(nullptr) {} - ~ArmedResponse() override; + inline ActuatorOutputStatus() : ActuatorOutputStatus(nullptr) {} + ~ActuatorOutputStatus() override; template - explicit PROTOBUF_CONSTEXPR ArmedResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ActuatorOutputStatus(::google::protobuf::internal::ConstantInitialized); - inline ArmedResponse(const ArmedResponse& from) - : ArmedResponse(nullptr, from) {} - ArmedResponse(ArmedResponse&& from) noexcept - : ArmedResponse() { + inline ActuatorOutputStatus(const ActuatorOutputStatus& from) + : ActuatorOutputStatus(nullptr, from) {} + ActuatorOutputStatus(ActuatorOutputStatus&& from) noexcept + : ActuatorOutputStatus() { *this = ::std::move(from); } - inline ArmedResponse& operator=(const ArmedResponse& from) { + inline ActuatorOutputStatus& operator=(const ActuatorOutputStatus& from) { CopyFrom(from); return *this; } - inline ArmedResponse& operator=(ArmedResponse&& from) noexcept { + inline ActuatorOutputStatus& operator=(ActuatorOutputStatus&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -15818,20 +15980,20 @@ class ArmedResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ArmedResponse& default_instance() { + static const ActuatorOutputStatus& default_instance() { return *internal_default_instance(); } - static inline const ArmedResponse* internal_default_instance() { - return reinterpret_cast( - &_ArmedResponse_default_instance_); + static inline const ActuatorOutputStatus* internal_default_instance() { + return reinterpret_cast( + &_ActuatorOutputStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 127; - friend void swap(ArmedResponse& a, ArmedResponse& b) { + friend void swap(ActuatorOutputStatus& a, ActuatorOutputStatus& b) { a.Swap(&b); } - inline void Swap(ArmedResponse* other) { + inline void Swap(ActuatorOutputStatus* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -15844,7 +16006,7 @@ class ArmedResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ArmedResponse* other) { + void UnsafeArenaSwap(ActuatorOutputStatus* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -15852,14 +16014,14 @@ class ArmedResponse final : // implements Message ---------------------------------------------- - ArmedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ActuatorOutputStatus* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ArmedResponse& from); + void CopyFrom(const ActuatorOutputStatus& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ArmedResponse& from) { - ArmedResponse::MergeImpl(*this, from); + void MergeFrom( const ActuatorOutputStatus& from) { + ActuatorOutputStatus::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -15877,16 +16039,16 @@ class ArmedResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ArmedResponse* other); + void InternalSwap(ActuatorOutputStatus* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.ArmedResponse"; + return "mavsdk.rpc.telemetry.ActuatorOutputStatus"; } protected: - explicit ArmedResponse(::google::protobuf::Arena* arena); - ArmedResponse(::google::protobuf::Arena* arena, const ArmedResponse& from); + explicit ActuatorOutputStatus(::google::protobuf::Arena* arena); + ActuatorOutputStatus(::google::protobuf::Arena* arena, const ActuatorOutputStatus& from); public: static const ClassData _class_data_; @@ -15899,25 +16061,44 @@ class ArmedResponse final : // accessors ------------------------------------------------------- enum : int { - kIsArmedFieldNumber = 1, + kActuatorFieldNumber = 2, + kActiveFieldNumber = 1, }; - // bool is_armed = 1; - void clear_is_armed() ; - bool is_armed() const; - void set_is_armed(bool value); + // repeated float actuator = 2; + int actuator_size() const; + private: + int _internal_actuator_size() const; + + public: + void clear_actuator() ; + float actuator(int index) const; + void set_actuator(int index, float value); + void add_actuator(float value); + const ::google::protobuf::RepeatedField& actuator() const; + ::google::protobuf::RepeatedField* mutable_actuator(); private: - bool _internal_is_armed() const; - void _internal_set_is_armed(bool value); + const ::google::protobuf::RepeatedField& _internal_actuator() const; + ::google::protobuf::RepeatedField* _internal_mutable_actuator(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ArmedResponse) + // uint32 active = 1 [(.mavsdk.options.default_value) = "0"]; + void clear_active() ; + ::uint32_t active() const; + void set_active(::uint32_t value); + + private: + ::uint32_t _internal_active() const; + void _internal_set_active(::uint32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorOutputStatus) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -15934,7 +16115,8 @@ class ArmedResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - bool is_armed_; + ::google::protobuf::RepeatedField actuator_; + ::uint32_t active_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -15942,26 +16124,26 @@ class ArmedResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class AngularVelocityFrd final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AngularVelocityFrd) */ { +class ActuatorControlTarget final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorControlTarget) */ { public: - inline AngularVelocityFrd() : AngularVelocityFrd(nullptr) {} - ~AngularVelocityFrd() override; + inline ActuatorControlTarget() : ActuatorControlTarget(nullptr) {} + ~ActuatorControlTarget() override; template - explicit PROTOBUF_CONSTEXPR AngularVelocityFrd(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ActuatorControlTarget(::google::protobuf::internal::ConstantInitialized); - inline AngularVelocityFrd(const AngularVelocityFrd& from) - : AngularVelocityFrd(nullptr, from) {} - AngularVelocityFrd(AngularVelocityFrd&& from) noexcept - : AngularVelocityFrd() { + inline ActuatorControlTarget(const ActuatorControlTarget& from) + : ActuatorControlTarget(nullptr, from) {} + ActuatorControlTarget(ActuatorControlTarget&& from) noexcept + : ActuatorControlTarget() { *this = ::std::move(from); } - inline AngularVelocityFrd& operator=(const AngularVelocityFrd& from) { + inline ActuatorControlTarget& operator=(const ActuatorControlTarget& from) { CopyFrom(from); return *this; } - inline AngularVelocityFrd& operator=(AngularVelocityFrd&& from) noexcept { + inline ActuatorControlTarget& operator=(ActuatorControlTarget&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -15993,20 +16175,20 @@ class AngularVelocityFrd final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const AngularVelocityFrd& default_instance() { + static const ActuatorControlTarget& default_instance() { return *internal_default_instance(); } - static inline const AngularVelocityFrd* internal_default_instance() { - return reinterpret_cast( - &_AngularVelocityFrd_default_instance_); + static inline const ActuatorControlTarget* internal_default_instance() { + return reinterpret_cast( + &_ActuatorControlTarget_default_instance_); } static constexpr int kIndexInFileMessages = - 148; + 126; - friend void swap(AngularVelocityFrd& a, AngularVelocityFrd& b) { + friend void swap(ActuatorControlTarget& a, ActuatorControlTarget& b) { a.Swap(&b); } - inline void Swap(AngularVelocityFrd* other) { + inline void Swap(ActuatorControlTarget* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -16019,7 +16201,7 @@ class AngularVelocityFrd final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(AngularVelocityFrd* other) { + void UnsafeArenaSwap(ActuatorControlTarget* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -16027,14 +16209,14 @@ class AngularVelocityFrd final : // implements Message ---------------------------------------------- - AngularVelocityFrd* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ActuatorControlTarget* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AngularVelocityFrd& from); + void CopyFrom(const ActuatorControlTarget& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AngularVelocityFrd& from) { - AngularVelocityFrd::MergeImpl(*this, from); + void MergeFrom( const ActuatorControlTarget& from) { + ActuatorControlTarget::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -16052,16 +16234,16 @@ class AngularVelocityFrd final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(AngularVelocityFrd* other); + void InternalSwap(ActuatorControlTarget* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.AngularVelocityFrd"; + return "mavsdk.rpc.telemetry.ActuatorControlTarget"; } protected: - explicit AngularVelocityFrd(::google::protobuf::Arena* arena); - AngularVelocityFrd(::google::protobuf::Arena* arena, const AngularVelocityFrd& from); + explicit ActuatorControlTarget(::google::protobuf::Arena* arena); + ActuatorControlTarget(::google::protobuf::Arena* arena, const ActuatorControlTarget& from); public: static const ClassData _class_data_; @@ -16074,47 +16256,44 @@ class AngularVelocityFrd final : // accessors ------------------------------------------------------- enum : int { - kForwardRadSFieldNumber = 1, - kRightRadSFieldNumber = 2, - kDownRadSFieldNumber = 3, + kControlsFieldNumber = 2, + kGroupFieldNumber = 1, }; - // float forward_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_forward_rad_s() ; - float forward_rad_s() const; - void set_forward_rad_s(float value); - + // repeated float controls = 2; + int controls_size() const; private: - float _internal_forward_rad_s() const; - void _internal_set_forward_rad_s(float value); + int _internal_controls_size() const; public: - // float right_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_right_rad_s() ; - float right_rad_s() const; - void set_right_rad_s(float value); + void clear_controls() ; + float controls(int index) const; + void set_controls(int index, float value); + void add_controls(float value); + const ::google::protobuf::RepeatedField& controls() const; + ::google::protobuf::RepeatedField* mutable_controls(); private: - float _internal_right_rad_s() const; - void _internal_set_right_rad_s(float value); + const ::google::protobuf::RepeatedField& _internal_controls() const; + ::google::protobuf::RepeatedField* _internal_mutable_controls(); public: - // float down_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_down_rad_s() ; - float down_rad_s() const; - void set_down_rad_s(float value); + // int32 group = 1 [(.mavsdk.options.default_value) = "0"]; + void clear_group() ; + ::int32_t group() const; + void set_group(::int32_t value); private: - float _internal_down_rad_s() const; - void _internal_set_down_rad_s(float value); + ::int32_t _internal_group() const; + void _internal_set_group(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AngularVelocityFrd) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorControlTarget) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -16131,9 +16310,8 @@ class AngularVelocityFrd final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float forward_rad_s_; - float right_rad_s_; - float down_rad_s_; + ::google::protobuf::RepeatedField controls_; + ::int32_t group_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -16141,26 +16319,26 @@ class AngularVelocityFrd final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class AngularVelocityBody final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AngularVelocityBody) */ { +class AccelerationFrd final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AccelerationFrd) */ { public: - inline AngularVelocityBody() : AngularVelocityBody(nullptr) {} - ~AngularVelocityBody() override; + inline AccelerationFrd() : AccelerationFrd(nullptr) {} + ~AccelerationFrd() override; template - explicit PROTOBUF_CONSTEXPR AngularVelocityBody(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR AccelerationFrd(::google::protobuf::internal::ConstantInitialized); - inline AngularVelocityBody(const AngularVelocityBody& from) - : AngularVelocityBody(nullptr, from) {} - AngularVelocityBody(AngularVelocityBody&& from) noexcept - : AngularVelocityBody() { + inline AccelerationFrd(const AccelerationFrd& from) + : AccelerationFrd(nullptr, from) {} + AccelerationFrd(AccelerationFrd&& from) noexcept + : AccelerationFrd() { *this = ::std::move(from); } - inline AngularVelocityBody& operator=(const AngularVelocityBody& from) { + inline AccelerationFrd& operator=(const AccelerationFrd& from) { CopyFrom(from); return *this; } - inline AngularVelocityBody& operator=(AngularVelocityBody&& from) noexcept { + inline AccelerationFrd& operator=(AccelerationFrd&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -16192,20 +16370,20 @@ class AngularVelocityBody final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const AngularVelocityBody& default_instance() { + static const AccelerationFrd& default_instance() { return *internal_default_instance(); } - static inline const AngularVelocityBody* internal_default_instance() { - return reinterpret_cast( - &_AngularVelocityBody_default_instance_); + static inline const AccelerationFrd* internal_default_instance() { + return reinterpret_cast( + &_AccelerationFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 127; + 139; - friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { + friend void swap(AccelerationFrd& a, AccelerationFrd& b) { a.Swap(&b); } - inline void Swap(AngularVelocityBody* other) { + inline void Swap(AccelerationFrd* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -16218,7 +16396,7 @@ class AngularVelocityBody final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(AngularVelocityBody* other) { + void UnsafeArenaSwap(AccelerationFrd* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -16226,14 +16404,14 @@ class AngularVelocityBody final : // implements Message ---------------------------------------------- - AngularVelocityBody* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + AccelerationFrd* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AngularVelocityBody& from); + void CopyFrom(const AccelerationFrd& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AngularVelocityBody& from) { - AngularVelocityBody::MergeImpl(*this, from); + void MergeFrom( const AccelerationFrd& from) { + AccelerationFrd::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -16251,16 +16429,16 @@ class AngularVelocityBody final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(AngularVelocityBody* other); + void InternalSwap(AccelerationFrd* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.AngularVelocityBody"; + return "mavsdk.rpc.telemetry.AccelerationFrd"; } protected: - explicit AngularVelocityBody(::google::protobuf::Arena* arena); - AngularVelocityBody(::google::protobuf::Arena* arena, const AngularVelocityBody& from); + explicit AccelerationFrd(::google::protobuf::Arena* arena); + AccelerationFrd(::google::protobuf::Arena* arena, const AccelerationFrd& from); public: static const ClassData _class_data_; @@ -16273,41 +16451,41 @@ class AngularVelocityBody final : // accessors ------------------------------------------------------- enum : int { - kRollRadSFieldNumber = 1, - kPitchRadSFieldNumber = 2, - kYawRadSFieldNumber = 3, + kForwardMS2FieldNumber = 1, + kRightMS2FieldNumber = 2, + kDownMS2FieldNumber = 3, }; - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_roll_rad_s() ; - float roll_rad_s() const; - void set_roll_rad_s(float value); + // float forward_m_s2 = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_forward_m_s2() ; + float forward_m_s2() const; + void set_forward_m_s2(float value); private: - float _internal_roll_rad_s() const; - void _internal_set_roll_rad_s(float value); + float _internal_forward_m_s2() const; + void _internal_set_forward_m_s2(float value); public: - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_pitch_rad_s() ; - float pitch_rad_s() const; - void set_pitch_rad_s(float value); + // float right_m_s2 = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_right_m_s2() ; + float right_m_s2() const; + void set_right_m_s2(float value); private: - float _internal_pitch_rad_s() const; - void _internal_set_pitch_rad_s(float value); + float _internal_right_m_s2() const; + void _internal_set_right_m_s2(float value); public: - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_yaw_rad_s() ; - float yaw_rad_s() const; - void set_yaw_rad_s(float value); + // float down_m_s2 = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_down_m_s2() ; + float down_m_s2() const; + void set_down_m_s2(float value); private: - float _internal_yaw_rad_s() const; - void _internal_set_yaw_rad_s(float value); + float _internal_down_m_s2() const; + void _internal_set_down_m_s2(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AngularVelocityBody) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AccelerationFrd) private: class _Internal; @@ -16330,9 +16508,9 @@ class AngularVelocityBody final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float roll_rad_s_; - float pitch_rad_s_; - float yaw_rad_s_; + float forward_m_s2_; + float right_m_s2_; + float down_m_s2_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -16340,26 +16518,26 @@ class AngularVelocityBody final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class Altitude final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Altitude) */ { +class VelocityNedResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.VelocityNedResponse) */ { public: - inline Altitude() : Altitude(nullptr) {} - ~Altitude() override; + inline VelocityNedResponse() : VelocityNedResponse(nullptr) {} + ~VelocityNedResponse() override; template - explicit PROTOBUF_CONSTEXPR Altitude(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR VelocityNedResponse(::google::protobuf::internal::ConstantInitialized); - inline Altitude(const Altitude& from) - : Altitude(nullptr, from) {} - Altitude(Altitude&& from) noexcept - : Altitude() { + inline VelocityNedResponse(const VelocityNedResponse& from) + : VelocityNedResponse(nullptr, from) {} + VelocityNedResponse(VelocityNedResponse&& from) noexcept + : VelocityNedResponse() { *this = ::std::move(from); } - inline Altitude& operator=(const Altitude& from) { + inline VelocityNedResponse& operator=(const VelocityNedResponse& from) { CopyFrom(from); return *this; } - inline Altitude& operator=(Altitude&& from) noexcept { + inline VelocityNedResponse& operator=(VelocityNedResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -16391,20 +16569,20 @@ class Altitude final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Altitude& default_instance() { + static const VelocityNedResponse& default_instance() { return *internal_default_instance(); } - static inline const Altitude* internal_default_instance() { - return reinterpret_cast( - &_Altitude_default_instance_); + static inline const VelocityNedResponse* internal_default_instance() { + return reinterpret_cast( + &_VelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 152; + 19; - friend void swap(Altitude& a, Altitude& b) { + friend void swap(VelocityNedResponse& a, VelocityNedResponse& b) { a.Swap(&b); } - inline void Swap(Altitude* other) { + inline void Swap(VelocityNedResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -16417,7 +16595,7 @@ class Altitude final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Altitude* other) { + void UnsafeArenaSwap(VelocityNedResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -16425,14 +16603,14 @@ class Altitude final : // implements Message ---------------------------------------------- - Altitude* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + VelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Altitude& from); + void CopyFrom(const VelocityNedResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Altitude& from) { - Altitude::MergeImpl(*this, from); + void MergeFrom( const VelocityNedResponse& from) { + VelocityNedResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -16450,16 +16628,16 @@ class Altitude final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Altitude* other); + void InternalSwap(VelocityNedResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Altitude"; + return "mavsdk.rpc.telemetry.VelocityNedResponse"; } protected: - explicit Altitude(::google::protobuf::Arena* arena); - Altitude(::google::protobuf::Arena* arena, const Altitude& from); + explicit VelocityNedResponse(::google::protobuf::Arena* arena); + VelocityNedResponse(::google::protobuf::Arena* arena, const VelocityNedResponse& from); public: static const ClassData _class_data_; @@ -16472,80 +16650,30 @@ class Altitude final : // accessors ------------------------------------------------------- enum : int { - kAltitudeMonotonicMFieldNumber = 1, - kAltitudeAmslMFieldNumber = 2, - kAltitudeLocalMFieldNumber = 3, - kAltitudeRelativeMFieldNumber = 4, - kAltitudeTerrainMFieldNumber = 5, - kBottomClearanceMFieldNumber = 6, + kVelocityNedFieldNumber = 1, }; - // float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_monotonic_m() ; - float altitude_monotonic_m() const; - void set_altitude_monotonic_m(float value); - - private: - float _internal_altitude_monotonic_m() const; - void _internal_set_altitude_monotonic_m(float value); - - public: - // float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_amsl_m() ; - float altitude_amsl_m() const; - void set_altitude_amsl_m(float value); - - private: - float _internal_altitude_amsl_m() const; - void _internal_set_altitude_amsl_m(float value); - - public: - // float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_local_m() ; - float altitude_local_m() const; - void set_altitude_local_m(float value); - - private: - float _internal_altitude_local_m() const; - void _internal_set_altitude_local_m(float value); - - public: - // float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_relative_m() ; - float altitude_relative_m() const; - void set_altitude_relative_m(float value); - - private: - float _internal_altitude_relative_m() const; - void _internal_set_altitude_relative_m(float value); - - public: - // float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; - void clear_altitude_terrain_m() ; - float altitude_terrain_m() const; - void set_altitude_terrain_m(float value); - - private: - float _internal_altitude_terrain_m() const; - void _internal_set_altitude_terrain_m(float value); - - public: - // float bottom_clearance_m = 6 [(.mavsdk.options.default_value) = "NaN"]; - void clear_bottom_clearance_m() ; - float bottom_clearance_m() const; - void set_bottom_clearance_m(float value); + // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; + bool has_velocity_ned() const; + void clear_velocity_ned() ; + const ::mavsdk::rpc::telemetry::VelocityNed& velocity_ned() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityNed* release_velocity_ned(); + ::mavsdk::rpc::telemetry::VelocityNed* mutable_velocity_ned(); + void set_allocated_velocity_ned(::mavsdk::rpc::telemetry::VelocityNed* value); + void unsafe_arena_set_allocated_velocity_ned(::mavsdk::rpc::telemetry::VelocityNed* value); + ::mavsdk::rpc::telemetry::VelocityNed* unsafe_arena_release_velocity_ned(); private: - float _internal_bottom_clearance_m() const; - void _internal_set_bottom_clearance_m(float value); + const ::mavsdk::rpc::telemetry::VelocityNed& _internal_velocity_ned() const; + ::mavsdk::rpc::telemetry::VelocityNed* _internal_mutable_velocity_ned(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Altitude) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.VelocityNedResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 6, 0, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -16562,39 +16690,35 @@ class Altitude final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float altitude_monotonic_m_; - float altitude_amsl_m_; - float altitude_local_m_; - float altitude_relative_m_; - float altitude_terrain_m_; - float bottom_clearance_m_; + ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry::VelocityNed* velocity_ned_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class ActuatorOutputStatus final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorOutputStatus) */ { +class StatusTextResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusTextResponse) */ { public: - inline ActuatorOutputStatus() : ActuatorOutputStatus(nullptr) {} - ~ActuatorOutputStatus() override; + inline StatusTextResponse() : StatusTextResponse(nullptr) {} + ~StatusTextResponse() override; template - explicit PROTOBUF_CONSTEXPR ActuatorOutputStatus(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR StatusTextResponse(::google::protobuf::internal::ConstantInitialized); - inline ActuatorOutputStatus(const ActuatorOutputStatus& from) - : ActuatorOutputStatus(nullptr, from) {} - ActuatorOutputStatus(ActuatorOutputStatus&& from) noexcept - : ActuatorOutputStatus() { + inline StatusTextResponse(const StatusTextResponse& from) + : StatusTextResponse(nullptr, from) {} + StatusTextResponse(StatusTextResponse&& from) noexcept + : StatusTextResponse() { *this = ::std::move(from); } - inline ActuatorOutputStatus& operator=(const ActuatorOutputStatus& from) { + inline StatusTextResponse& operator=(const StatusTextResponse& from) { CopyFrom(from); return *this; } - inline ActuatorOutputStatus& operator=(ActuatorOutputStatus&& from) noexcept { + inline StatusTextResponse& operator=(StatusTextResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -16626,20 +16750,20 @@ class ActuatorOutputStatus final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ActuatorOutputStatus& default_instance() { + static const StatusTextResponse& default_instance() { return *internal_default_instance(); } - static inline const ActuatorOutputStatus* internal_default_instance() { - return reinterpret_cast( - &_ActuatorOutputStatus_default_instance_); + static inline const StatusTextResponse* internal_default_instance() { + return reinterpret_cast( + &_StatusTextResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 135; + 33; - friend void swap(ActuatorOutputStatus& a, ActuatorOutputStatus& b) { + friend void swap(StatusTextResponse& a, StatusTextResponse& b) { a.Swap(&b); } - inline void Swap(ActuatorOutputStatus* other) { + inline void Swap(StatusTextResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -16652,7 +16776,7 @@ class ActuatorOutputStatus final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ActuatorOutputStatus* other) { + void UnsafeArenaSwap(StatusTextResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -16660,14 +16784,14 @@ class ActuatorOutputStatus final : // implements Message ---------------------------------------------- - ActuatorOutputStatus* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + StatusTextResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ActuatorOutputStatus& from); + void CopyFrom(const StatusTextResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ActuatorOutputStatus& from) { - ActuatorOutputStatus::MergeImpl(*this, from); + void MergeFrom( const StatusTextResponse& from) { + StatusTextResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -16685,16 +16809,16 @@ class ActuatorOutputStatus final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ActuatorOutputStatus* other); + void InternalSwap(StatusTextResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.ActuatorOutputStatus"; + return "mavsdk.rpc.telemetry.StatusTextResponse"; } protected: - explicit ActuatorOutputStatus(::google::protobuf::Arena* arena); - ActuatorOutputStatus(::google::protobuf::Arena* arena, const ActuatorOutputStatus& from); + explicit StatusTextResponse(::google::protobuf::Arena* arena); + StatusTextResponse(::google::protobuf::Arena* arena, const StatusTextResponse& from); public: static const ClassData _class_data_; @@ -16707,44 +16831,30 @@ class ActuatorOutputStatus final : // accessors ------------------------------------------------------- enum : int { - kActuatorFieldNumber = 2, - kActiveFieldNumber = 1, + kStatusTextFieldNumber = 1, }; - // repeated float actuator = 2; - int actuator_size() const; - private: - int _internal_actuator_size() const; - - public: - void clear_actuator() ; - float actuator(int index) const; - void set_actuator(int index, float value); - void add_actuator(float value); - const ::google::protobuf::RepeatedField& actuator() const; - ::google::protobuf::RepeatedField* mutable_actuator(); - - private: - const ::google::protobuf::RepeatedField& _internal_actuator() const; - ::google::protobuf::RepeatedField* _internal_mutable_actuator(); - - public: - // uint32 active = 1 [(.mavsdk.options.default_value) = "0"]; - void clear_active() ; - ::uint32_t active() const; - void set_active(::uint32_t value); + // .mavsdk.rpc.telemetry.StatusText status_text = 1; + bool has_status_text() const; + void clear_status_text() ; + const ::mavsdk::rpc::telemetry::StatusText& status_text() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::StatusText* release_status_text(); + ::mavsdk::rpc::telemetry::StatusText* mutable_status_text(); + void set_allocated_status_text(::mavsdk::rpc::telemetry::StatusText* value); + void unsafe_arena_set_allocated_status_text(::mavsdk::rpc::telemetry::StatusText* value); + ::mavsdk::rpc::telemetry::StatusText* unsafe_arena_release_status_text(); private: - ::uint32_t _internal_active() const; - void _internal_set_active(::uint32_t value); + const ::mavsdk::rpc::telemetry::StatusText& _internal_status_text() const; + ::mavsdk::rpc::telemetry::StatusText* _internal_mutable_status_text(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorOutputStatus) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusTextResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -16761,35 +16871,35 @@ class ActuatorOutputStatus final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::RepeatedField actuator_; - ::uint32_t active_; + ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry::StatusText* status_text_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class ActuatorControlTarget final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorControlTarget) */ { +class SetRateVtolStateResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVtolStateResponse) */ { public: - inline ActuatorControlTarget() : ActuatorControlTarget(nullptr) {} - ~ActuatorControlTarget() override; + inline SetRateVtolStateResponse() : SetRateVtolStateResponse(nullptr) {} + ~SetRateVtolStateResponse() override; template - explicit PROTOBUF_CONSTEXPR ActuatorControlTarget(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateVtolStateResponse(::google::protobuf::internal::ConstantInitialized); - inline ActuatorControlTarget(const ActuatorControlTarget& from) - : ActuatorControlTarget(nullptr, from) {} - ActuatorControlTarget(ActuatorControlTarget&& from) noexcept - : ActuatorControlTarget() { + inline SetRateVtolStateResponse(const SetRateVtolStateResponse& from) + : SetRateVtolStateResponse(nullptr, from) {} + SetRateVtolStateResponse(SetRateVtolStateResponse&& from) noexcept + : SetRateVtolStateResponse() { *this = ::std::move(from); } - inline ActuatorControlTarget& operator=(const ActuatorControlTarget& from) { + inline SetRateVtolStateResponse& operator=(const SetRateVtolStateResponse& from) { CopyFrom(from); return *this; } - inline ActuatorControlTarget& operator=(ActuatorControlTarget&& from) noexcept { + inline SetRateVtolStateResponse& operator=(SetRateVtolStateResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -16821,20 +16931,20 @@ class ActuatorControlTarget final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ActuatorControlTarget& default_instance() { + static const SetRateVtolStateResponse& default_instance() { return *internal_default_instance(); } - static inline const ActuatorControlTarget* internal_default_instance() { - return reinterpret_cast( - &_ActuatorControlTarget_default_instance_); + static inline const SetRateVtolStateResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateVtolStateResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 134; + 73; - friend void swap(ActuatorControlTarget& a, ActuatorControlTarget& b) { + friend void swap(SetRateVtolStateResponse& a, SetRateVtolStateResponse& b) { a.Swap(&b); } - inline void Swap(ActuatorControlTarget* other) { + inline void Swap(SetRateVtolStateResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -16847,7 +16957,7 @@ class ActuatorControlTarget final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ActuatorControlTarget* other) { + void UnsafeArenaSwap(SetRateVtolStateResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -16855,14 +16965,14 @@ class ActuatorControlTarget final : // implements Message ---------------------------------------------- - ActuatorControlTarget* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateVtolStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ActuatorControlTarget& from); + void CopyFrom(const SetRateVtolStateResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ActuatorControlTarget& from) { - ActuatorControlTarget::MergeImpl(*this, from); + void MergeFrom( const SetRateVtolStateResponse& from) { + SetRateVtolStateResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -16880,16 +16990,16 @@ class ActuatorControlTarget final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ActuatorControlTarget* other); + void InternalSwap(SetRateVtolStateResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.ActuatorControlTarget"; + return "mavsdk.rpc.telemetry.SetRateVtolStateResponse"; } protected: - explicit ActuatorControlTarget(::google::protobuf::Arena* arena); - ActuatorControlTarget(::google::protobuf::Arena* arena, const ActuatorControlTarget& from); + explicit SetRateVtolStateResponse(::google::protobuf::Arena* arena); + SetRateVtolStateResponse(::google::protobuf::Arena* arena, const SetRateVtolStateResponse& from); public: static const ClassData _class_data_; @@ -16902,44 +17012,30 @@ class ActuatorControlTarget final : // accessors ------------------------------------------------------- enum : int { - kControlsFieldNumber = 2, - kGroupFieldNumber = 1, + kTelemetryResultFieldNumber = 1, }; - // repeated float controls = 2; - int controls_size() const; - private: - int _internal_controls_size() const; - - public: - void clear_controls() ; - float controls(int index) const; - void set_controls(int index, float value); - void add_controls(float value); - const ::google::protobuf::RepeatedField& controls() const; - ::google::protobuf::RepeatedField* mutable_controls(); + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + void clear_telemetry_result() ; + const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); + ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); + void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); private: - const ::google::protobuf::RepeatedField& _internal_controls() const; - ::google::protobuf::RepeatedField* _internal_mutable_controls(); + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // int32 group = 1 [(.mavsdk.options.default_value) = "0"]; - void clear_group() ; - ::int32_t group() const; - void set_group(::int32_t value); - - private: - ::int32_t _internal_group() const; - void _internal_set_group(::int32_t value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorControlTarget) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVtolStateResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 0, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -16956,35 +17052,35 @@ class ActuatorControlTarget final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::RepeatedField controls_; - ::int32_t group_; + ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class AccelerationFrd final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AccelerationFrd) */ { +class SetRateVelocityNedResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVelocityNedResponse) */ { public: - inline AccelerationFrd() : AccelerationFrd(nullptr) {} - ~AccelerationFrd() override; + inline SetRateVelocityNedResponse() : SetRateVelocityNedResponse(nullptr) {} + ~SetRateVelocityNedResponse() override; template - explicit PROTOBUF_CONSTEXPR AccelerationFrd(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateVelocityNedResponse(::google::protobuf::internal::ConstantInitialized); - inline AccelerationFrd(const AccelerationFrd& from) - : AccelerationFrd(nullptr, from) {} - AccelerationFrd(AccelerationFrd&& from) noexcept - : AccelerationFrd() { + inline SetRateVelocityNedResponse(const SetRateVelocityNedResponse& from) + : SetRateVelocityNedResponse(nullptr, from) {} + SetRateVelocityNedResponse(SetRateVelocityNedResponse&& from) noexcept + : SetRateVelocityNedResponse() { *this = ::std::move(from); } - inline AccelerationFrd& operator=(const AccelerationFrd& from) { + inline SetRateVelocityNedResponse& operator=(const SetRateVelocityNedResponse& from) { CopyFrom(from); return *this; } - inline AccelerationFrd& operator=(AccelerationFrd&& from) noexcept { + inline SetRateVelocityNedResponse& operator=(SetRateVelocityNedResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17016,20 +17112,20 @@ class AccelerationFrd final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const AccelerationFrd& default_instance() { + static const SetRateVelocityNedResponse& default_instance() { return *internal_default_instance(); } - static inline const AccelerationFrd* internal_default_instance() { - return reinterpret_cast( - &_AccelerationFrd_default_instance_); + static inline const SetRateVelocityNedResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateVelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 147; + 81; - friend void swap(AccelerationFrd& a, AccelerationFrd& b) { + friend void swap(SetRateVelocityNedResponse& a, SetRateVelocityNedResponse& b) { a.Swap(&b); } - inline void Swap(AccelerationFrd* other) { + inline void Swap(SetRateVelocityNedResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17042,7 +17138,7 @@ class AccelerationFrd final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(AccelerationFrd* other) { + void UnsafeArenaSwap(SetRateVelocityNedResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17050,14 +17146,14 @@ class AccelerationFrd final : // implements Message ---------------------------------------------- - AccelerationFrd* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AccelerationFrd& from); + void CopyFrom(const SetRateVelocityNedResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AccelerationFrd& from) { - AccelerationFrd::MergeImpl(*this, from); + void MergeFrom( const SetRateVelocityNedResponse& from) { + SetRateVelocityNedResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17075,16 +17171,16 @@ class AccelerationFrd final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(AccelerationFrd* other); + void InternalSwap(SetRateVelocityNedResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.AccelerationFrd"; + return "mavsdk.rpc.telemetry.SetRateVelocityNedResponse"; } protected: - explicit AccelerationFrd(::google::protobuf::Arena* arena); - AccelerationFrd(::google::protobuf::Arena* arena, const AccelerationFrd& from); + explicit SetRateVelocityNedResponse(::google::protobuf::Arena* arena); + SetRateVelocityNedResponse(::google::protobuf::Arena* arena, const SetRateVelocityNedResponse& from); public: static const ClassData _class_data_; @@ -17097,47 +17193,30 @@ class AccelerationFrd final : // accessors ------------------------------------------------------- enum : int { - kForwardMS2FieldNumber = 1, - kRightMS2FieldNumber = 2, - kDownMS2FieldNumber = 3, + kTelemetryResultFieldNumber = 1, }; - // float forward_m_s2 = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_forward_m_s2() ; - float forward_m_s2() const; - void set_forward_m_s2(float value); - - private: - float _internal_forward_m_s2() const; - void _internal_set_forward_m_s2(float value); - - public: - // float right_m_s2 = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_right_m_s2() ; - float right_m_s2() const; - void set_right_m_s2(float value); - - private: - float _internal_right_m_s2() const; - void _internal_set_right_m_s2(float value); - - public: - // float down_m_s2 = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_down_m_s2() ; - float down_m_s2() const; - void set_down_m_s2(float value); + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + void clear_telemetry_result() ; + const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); + ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); + void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); private: - float _internal_down_m_s2() const; - void _internal_set_down_m_s2(float value); + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AccelerationFrd) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVelocityNedResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -17154,36 +17233,35 @@ class AccelerationFrd final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float forward_m_s2_; - float right_m_s2_; - float down_m_s2_; + ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class VelocityNedResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.VelocityNedResponse) */ { +class SetRateUnixEpochTimeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse) */ { public: - inline VelocityNedResponse() : VelocityNedResponse(nullptr) {} - ~VelocityNedResponse() override; + inline SetRateUnixEpochTimeResponse() : SetRateUnixEpochTimeResponse(nullptr) {} + ~SetRateUnixEpochTimeResponse() override; template - explicit PROTOBUF_CONSTEXPR VelocityNedResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateUnixEpochTimeResponse(::google::protobuf::internal::ConstantInitialized); - inline VelocityNedResponse(const VelocityNedResponse& from) - : VelocityNedResponse(nullptr, from) {} - VelocityNedResponse(VelocityNedResponse&& from) noexcept - : VelocityNedResponse() { + inline SetRateUnixEpochTimeResponse(const SetRateUnixEpochTimeResponse& from) + : SetRateUnixEpochTimeResponse(nullptr, from) {} + SetRateUnixEpochTimeResponse(SetRateUnixEpochTimeResponse&& from) noexcept + : SetRateUnixEpochTimeResponse() { *this = ::std::move(from); } - inline VelocityNedResponse& operator=(const VelocityNedResponse& from) { + inline SetRateUnixEpochTimeResponse& operator=(const SetRateUnixEpochTimeResponse& from) { CopyFrom(from); return *this; } - inline VelocityNedResponse& operator=(VelocityNedResponse&& from) noexcept { + inline SetRateUnixEpochTimeResponse& operator=(SetRateUnixEpochTimeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17215,20 +17293,20 @@ class VelocityNedResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const VelocityNedResponse& default_instance() { + static const SetRateUnixEpochTimeResponse& default_instance() { return *internal_default_instance(); } - static inline const VelocityNedResponse* internal_default_instance() { - return reinterpret_cast( - &_VelocityNedResponse_default_instance_); + static inline const SetRateUnixEpochTimeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateUnixEpochTimeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 108; - friend void swap(VelocityNedResponse& a, VelocityNedResponse& b) { + friend void swap(SetRateUnixEpochTimeResponse& a, SetRateUnixEpochTimeResponse& b) { a.Swap(&b); } - inline void Swap(VelocityNedResponse* other) { + inline void Swap(SetRateUnixEpochTimeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17241,7 +17319,7 @@ class VelocityNedResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(VelocityNedResponse* other) { + void UnsafeArenaSwap(SetRateUnixEpochTimeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17249,14 +17327,14 @@ class VelocityNedResponse final : // implements Message ---------------------------------------------- - VelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateUnixEpochTimeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const VelocityNedResponse& from); + void CopyFrom(const SetRateUnixEpochTimeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const VelocityNedResponse& from) { - VelocityNedResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateUnixEpochTimeResponse& from) { + SetRateUnixEpochTimeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17274,16 +17352,16 @@ class VelocityNedResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(VelocityNedResponse* other); + void InternalSwap(SetRateUnixEpochTimeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.VelocityNedResponse"; + return "mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse"; } protected: - explicit VelocityNedResponse(::google::protobuf::Arena* arena); - VelocityNedResponse(::google::protobuf::Arena* arena, const VelocityNedResponse& from); + explicit SetRateUnixEpochTimeResponse(::google::protobuf::Arena* arena); + SetRateUnixEpochTimeResponse(::google::protobuf::Arena* arena, const SetRateUnixEpochTimeResponse& from); public: static const ClassData _class_data_; @@ -17296,24 +17374,24 @@ class VelocityNedResponse final : // accessors ------------------------------------------------------- enum : int { - kVelocityNedFieldNumber = 1, + kTelemetryResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.VelocityNed velocity_ned = 1; - bool has_velocity_ned() const; - void clear_velocity_ned() ; - const ::mavsdk::rpc::telemetry::VelocityNed& velocity_ned() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityNed* release_velocity_ned(); - ::mavsdk::rpc::telemetry::VelocityNed* mutable_velocity_ned(); - void set_allocated_velocity_ned(::mavsdk::rpc::telemetry::VelocityNed* value); - void unsafe_arena_set_allocated_velocity_ned(::mavsdk::rpc::telemetry::VelocityNed* value); - ::mavsdk::rpc::telemetry::VelocityNed* unsafe_arena_release_velocity_ned(); + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + void clear_telemetry_result() ; + const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); + ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); + void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); private: - const ::mavsdk::rpc::telemetry::VelocityNed& _internal_velocity_ned() const; - ::mavsdk::rpc::telemetry::VelocityNed* _internal_mutable_velocity_ned(); + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.VelocityNedResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse) private: class _Internal; @@ -17338,33 +17416,33 @@ class VelocityNedResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::VelocityNed* velocity_ned_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class StatusTextResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusTextResponse) */ { +class SetRateScaledImuResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateScaledImuResponse) */ { public: - inline StatusTextResponse() : StatusTextResponse(nullptr) {} - ~StatusTextResponse() override; + inline SetRateScaledImuResponse() : SetRateScaledImuResponse(nullptr) {} + ~SetRateScaledImuResponse() override; template - explicit PROTOBUF_CONSTEXPR StatusTextResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateScaledImuResponse(::google::protobuf::internal::ConstantInitialized); - inline StatusTextResponse(const StatusTextResponse& from) - : StatusTextResponse(nullptr, from) {} - StatusTextResponse(StatusTextResponse&& from) noexcept - : StatusTextResponse() { + inline SetRateScaledImuResponse(const SetRateScaledImuResponse& from) + : SetRateScaledImuResponse(nullptr, from) {} + SetRateScaledImuResponse(SetRateScaledImuResponse&& from) noexcept + : SetRateScaledImuResponse() { *this = ::std::move(from); } - inline StatusTextResponse& operator=(const StatusTextResponse& from) { + inline SetRateScaledImuResponse& operator=(const SetRateScaledImuResponse& from) { CopyFrom(from); return *this; } - inline StatusTextResponse& operator=(StatusTextResponse&& from) noexcept { + inline SetRateScaledImuResponse& operator=(SetRateScaledImuResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17396,20 +17474,20 @@ class StatusTextResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const StatusTextResponse& default_instance() { + static const SetRateScaledImuResponse& default_instance() { return *internal_default_instance(); } - static inline const StatusTextResponse* internal_default_instance() { - return reinterpret_cast( - &_StatusTextResponse_default_instance_); + static inline const SetRateScaledImuResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateScaledImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 37; + 104; - friend void swap(StatusTextResponse& a, StatusTextResponse& b) { + friend void swap(SetRateScaledImuResponse& a, SetRateScaledImuResponse& b) { a.Swap(&b); } - inline void Swap(StatusTextResponse* other) { + inline void Swap(SetRateScaledImuResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17422,7 +17500,7 @@ class StatusTextResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(StatusTextResponse* other) { + void UnsafeArenaSwap(SetRateScaledImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17430,14 +17508,14 @@ class StatusTextResponse final : // implements Message ---------------------------------------------- - StatusTextResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateScaledImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const StatusTextResponse& from); + void CopyFrom(const SetRateScaledImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const StatusTextResponse& from) { - StatusTextResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateScaledImuResponse& from) { + SetRateScaledImuResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17455,16 +17533,16 @@ class StatusTextResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(StatusTextResponse* other); + void InternalSwap(SetRateScaledImuResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.StatusTextResponse"; + return "mavsdk.rpc.telemetry.SetRateScaledImuResponse"; } protected: - explicit StatusTextResponse(::google::protobuf::Arena* arena); - StatusTextResponse(::google::protobuf::Arena* arena, const StatusTextResponse& from); + explicit SetRateScaledImuResponse(::google::protobuf::Arena* arena); + SetRateScaledImuResponse(::google::protobuf::Arena* arena, const SetRateScaledImuResponse& from); public: static const ClassData _class_data_; @@ -17477,24 +17555,24 @@ class StatusTextResponse final : // accessors ------------------------------------------------------- enum : int { - kStatusTextFieldNumber = 1, + kTelemetryResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.StatusText status_text = 1; - bool has_status_text() const; - void clear_status_text() ; - const ::mavsdk::rpc::telemetry::StatusText& status_text() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::StatusText* release_status_text(); - ::mavsdk::rpc::telemetry::StatusText* mutable_status_text(); - void set_allocated_status_text(::mavsdk::rpc::telemetry::StatusText* value); - void unsafe_arena_set_allocated_status_text(::mavsdk::rpc::telemetry::StatusText* value); - ::mavsdk::rpc::telemetry::StatusText* unsafe_arena_release_status_text(); + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + void clear_telemetry_result() ; + const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); + ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); + void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); private: - const ::mavsdk::rpc::telemetry::StatusText& _internal_status_text() const; - ::mavsdk::rpc::telemetry::StatusText* _internal_mutable_status_text(); + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateScaledImuResponse) private: class _Internal; @@ -17519,33 +17597,33 @@ class StatusTextResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::StatusText* status_text_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateVtolStateResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVtolStateResponse) */ { +class SetRateRcStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRcStatusResponse) */ { public: - inline SetRateVtolStateResponse() : SetRateVtolStateResponse(nullptr) {} - ~SetRateVtolStateResponse() override; + inline SetRateRcStatusResponse() : SetRateRcStatusResponse(nullptr) {} + ~SetRateRcStatusResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateVtolStateResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateRcStatusResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateVtolStateResponse(const SetRateVtolStateResponse& from) - : SetRateVtolStateResponse(nullptr, from) {} - SetRateVtolStateResponse(SetRateVtolStateResponse&& from) noexcept - : SetRateVtolStateResponse() { + inline SetRateRcStatusResponse(const SetRateRcStatusResponse& from) + : SetRateRcStatusResponse(nullptr, from) {} + SetRateRcStatusResponse(SetRateRcStatusResponse&& from) noexcept + : SetRateRcStatusResponse() { *this = ::std::move(from); } - inline SetRateVtolStateResponse& operator=(const SetRateVtolStateResponse& from) { + inline SetRateRcStatusResponse& operator=(const SetRateRcStatusResponse& from) { CopyFrom(from); return *this; } - inline SetRateVtolStateResponse& operator=(SetRateVtolStateResponse&& from) noexcept { + inline SetRateRcStatusResponse& operator=(SetRateRcStatusResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17577,20 +17655,20 @@ class SetRateVtolStateResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateVtolStateResponse& default_instance() { + static const SetRateRcStatusResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateVtolStateResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateVtolStateResponse_default_instance_); + static inline const SetRateRcStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateRcStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 77; + 88; - friend void swap(SetRateVtolStateResponse& a, SetRateVtolStateResponse& b) { + friend void swap(SetRateRcStatusResponse& a, SetRateRcStatusResponse& b) { a.Swap(&b); } - inline void Swap(SetRateVtolStateResponse* other) { + inline void Swap(SetRateRcStatusResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17603,7 +17681,7 @@ class SetRateVtolStateResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateVtolStateResponse* other) { + void UnsafeArenaSwap(SetRateRcStatusResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17611,14 +17689,14 @@ class SetRateVtolStateResponse final : // implements Message ---------------------------------------------- - SetRateVtolStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateRcStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateVtolStateResponse& from); + void CopyFrom(const SetRateRcStatusResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateVtolStateResponse& from) { - SetRateVtolStateResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateRcStatusResponse& from) { + SetRateRcStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17636,16 +17714,16 @@ class SetRateVtolStateResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateVtolStateResponse* other); + void InternalSwap(SetRateRcStatusResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateVtolStateResponse"; + return "mavsdk.rpc.telemetry.SetRateRcStatusResponse"; } protected: - explicit SetRateVtolStateResponse(::google::protobuf::Arena* arena); - SetRateVtolStateResponse(::google::protobuf::Arena* arena, const SetRateVtolStateResponse& from); + explicit SetRateRcStatusResponse(::google::protobuf::Arena* arena); + SetRateRcStatusResponse(::google::protobuf::Arena* arena, const SetRateRcStatusResponse& from); public: static const ClassData _class_data_; @@ -17675,7 +17753,7 @@ class SetRateVtolStateResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVtolStateResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRcStatusResponse) private: class _Internal; @@ -17707,26 +17785,26 @@ class SetRateVtolStateResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateVelocityNedResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateVelocityNedResponse) */ { +class SetRateRawImuResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawImuResponse) */ { public: - inline SetRateVelocityNedResponse() : SetRateVelocityNedResponse(nullptr) {} - ~SetRateVelocityNedResponse() override; + inline SetRateRawImuResponse() : SetRateRawImuResponse(nullptr) {} + ~SetRateRawImuResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateVelocityNedResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateRawImuResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateVelocityNedResponse(const SetRateVelocityNedResponse& from) - : SetRateVelocityNedResponse(nullptr, from) {} - SetRateVelocityNedResponse(SetRateVelocityNedResponse&& from) noexcept - : SetRateVelocityNedResponse() { + inline SetRateRawImuResponse(const SetRateRawImuResponse& from) + : SetRateRawImuResponse(nullptr, from) {} + SetRateRawImuResponse(SetRateRawImuResponse&& from) noexcept + : SetRateRawImuResponse() { *this = ::std::move(from); } - inline SetRateVelocityNedResponse& operator=(const SetRateVelocityNedResponse& from) { + inline SetRateRawImuResponse& operator=(const SetRateRawImuResponse& from) { CopyFrom(from); return *this; } - inline SetRateVelocityNedResponse& operator=(SetRateVelocityNedResponse&& from) noexcept { + inline SetRateRawImuResponse& operator=(SetRateRawImuResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17758,20 +17836,20 @@ class SetRateVelocityNedResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateVelocityNedResponse& default_instance() { + static const SetRateRawImuResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateVelocityNedResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateVelocityNedResponse_default_instance_); + static inline const SetRateRawImuResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateRawImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 89; + 106; - friend void swap(SetRateVelocityNedResponse& a, SetRateVelocityNedResponse& b) { + friend void swap(SetRateRawImuResponse& a, SetRateRawImuResponse& b) { a.Swap(&b); } - inline void Swap(SetRateVelocityNedResponse* other) { + inline void Swap(SetRateRawImuResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17784,7 +17862,7 @@ class SetRateVelocityNedResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateVelocityNedResponse* other) { + void UnsafeArenaSwap(SetRateRawImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17792,14 +17870,14 @@ class SetRateVelocityNedResponse final : // implements Message ---------------------------------------------- - SetRateVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateRawImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateVelocityNedResponse& from); + void CopyFrom(const SetRateRawImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateVelocityNedResponse& from) { - SetRateVelocityNedResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateRawImuResponse& from) { + SetRateRawImuResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17817,16 +17895,16 @@ class SetRateVelocityNedResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateVelocityNedResponse* other); + void InternalSwap(SetRateRawImuResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateVelocityNedResponse"; + return "mavsdk.rpc.telemetry.SetRateRawImuResponse"; } protected: - explicit SetRateVelocityNedResponse(::google::protobuf::Arena* arena); - SetRateVelocityNedResponse(::google::protobuf::Arena* arena, const SetRateVelocityNedResponse& from); + explicit SetRateRawImuResponse(::google::protobuf::Arena* arena); + SetRateRawImuResponse(::google::protobuf::Arena* arena, const SetRateRawImuResponse& from); public: static const ClassData _class_data_; @@ -17856,7 +17934,7 @@ class SetRateVelocityNedResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateVelocityNedResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawImuResponse) private: class _Internal; @@ -17888,26 +17966,26 @@ class SetRateVelocityNedResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateUnixEpochTimeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse) */ { +class SetRatePositionVelocityNedResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse) */ { public: - inline SetRateUnixEpochTimeResponse() : SetRateUnixEpochTimeResponse(nullptr) {} - ~SetRateUnixEpochTimeResponse() override; + inline SetRatePositionVelocityNedResponse() : SetRatePositionVelocityNedResponse(nullptr) {} + ~SetRatePositionVelocityNedResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateUnixEpochTimeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRatePositionVelocityNedResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateUnixEpochTimeResponse(const SetRateUnixEpochTimeResponse& from) - : SetRateUnixEpochTimeResponse(nullptr, from) {} - SetRateUnixEpochTimeResponse(SetRateUnixEpochTimeResponse&& from) noexcept - : SetRateUnixEpochTimeResponse() { + inline SetRatePositionVelocityNedResponse(const SetRatePositionVelocityNedResponse& from) + : SetRatePositionVelocityNedResponse(nullptr, from) {} + SetRatePositionVelocityNedResponse(SetRatePositionVelocityNedResponse&& from) noexcept + : SetRatePositionVelocityNedResponse() { *this = ::std::move(from); } - inline SetRateUnixEpochTimeResponse& operator=(const SetRateUnixEpochTimeResponse& from) { + inline SetRatePositionVelocityNedResponse& operator=(const SetRatePositionVelocityNedResponse& from) { CopyFrom(from); return *this; } - inline SetRateUnixEpochTimeResponse& operator=(SetRateUnixEpochTimeResponse&& from) noexcept { + inline SetRatePositionVelocityNedResponse& operator=(SetRatePositionVelocityNedResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17939,20 +18017,20 @@ class SetRateUnixEpochTimeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateUnixEpochTimeResponse& default_instance() { + static const SetRatePositionVelocityNedResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateUnixEpochTimeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateUnixEpochTimeResponse_default_instance_); + static inline const SetRatePositionVelocityNedResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRatePositionVelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 116; + 96; - friend void swap(SetRateUnixEpochTimeResponse& a, SetRateUnixEpochTimeResponse& b) { + friend void swap(SetRatePositionVelocityNedResponse& a, SetRatePositionVelocityNedResponse& b) { a.Swap(&b); } - inline void Swap(SetRateUnixEpochTimeResponse* other) { + inline void Swap(SetRatePositionVelocityNedResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -17965,7 +18043,7 @@ class SetRateUnixEpochTimeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateUnixEpochTimeResponse* other) { + void UnsafeArenaSwap(SetRatePositionVelocityNedResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -17973,14 +18051,14 @@ class SetRateUnixEpochTimeResponse final : // implements Message ---------------------------------------------- - SetRateUnixEpochTimeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRatePositionVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateUnixEpochTimeResponse& from); + void CopyFrom(const SetRatePositionVelocityNedResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateUnixEpochTimeResponse& from) { - SetRateUnixEpochTimeResponse::MergeImpl(*this, from); + void MergeFrom( const SetRatePositionVelocityNedResponse& from) { + SetRatePositionVelocityNedResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -17998,16 +18076,16 @@ class SetRateUnixEpochTimeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateUnixEpochTimeResponse* other); + void InternalSwap(SetRatePositionVelocityNedResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse"; + return "mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse"; } protected: - explicit SetRateUnixEpochTimeResponse(::google::protobuf::Arena* arena); - SetRateUnixEpochTimeResponse(::google::protobuf::Arena* arena, const SetRateUnixEpochTimeResponse& from); + explicit SetRatePositionVelocityNedResponse(::google::protobuf::Arena* arena); + SetRatePositionVelocityNedResponse(::google::protobuf::Arena* arena, const SetRatePositionVelocityNedResponse& from); public: static const ClassData _class_data_; @@ -18037,7 +18115,7 @@ class SetRateUnixEpochTimeResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateUnixEpochTimeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse) private: class _Internal; @@ -18069,26 +18147,26 @@ class SetRateUnixEpochTimeResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateScaledImuResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateScaledImuResponse) */ { +class SetRatePositionResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionResponse) */ { public: - inline SetRateScaledImuResponse() : SetRateScaledImuResponse(nullptr) {} - ~SetRateScaledImuResponse() override; + inline SetRatePositionResponse() : SetRatePositionResponse(nullptr) {} + ~SetRatePositionResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateScaledImuResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRatePositionResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateScaledImuResponse(const SetRateScaledImuResponse& from) - : SetRateScaledImuResponse(nullptr, from) {} - SetRateScaledImuResponse(SetRateScaledImuResponse&& from) noexcept - : SetRateScaledImuResponse() { + inline SetRatePositionResponse(const SetRatePositionResponse& from) + : SetRatePositionResponse(nullptr, from) {} + SetRatePositionResponse(SetRatePositionResponse&& from) noexcept + : SetRatePositionResponse() { *this = ::std::move(from); } - inline SetRateScaledImuResponse& operator=(const SetRateScaledImuResponse& from) { + inline SetRatePositionResponse& operator=(const SetRatePositionResponse& from) { CopyFrom(from); return *this; } - inline SetRateScaledImuResponse& operator=(SetRateScaledImuResponse&& from) noexcept { + inline SetRatePositionResponse& operator=(SetRatePositionResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -18120,20 +18198,20 @@ class SetRateScaledImuResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateScaledImuResponse& default_instance() { + static const SetRatePositionResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateScaledImuResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateScaledImuResponse_default_instance_); + static inline const SetRatePositionResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRatePositionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 112; + 65; - friend void swap(SetRateScaledImuResponse& a, SetRateScaledImuResponse& b) { + friend void swap(SetRatePositionResponse& a, SetRatePositionResponse& b) { a.Swap(&b); } - inline void Swap(SetRateScaledImuResponse* other) { + inline void Swap(SetRatePositionResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -18146,7 +18224,7 @@ class SetRateScaledImuResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateScaledImuResponse* other) { + void UnsafeArenaSwap(SetRatePositionResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -18154,15 +18232,15 @@ class SetRateScaledImuResponse final : // implements Message ---------------------------------------------- - SetRateScaledImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRatePositionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateScaledImuResponse& from); + void CopyFrom(const SetRatePositionResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateScaledImuResponse& from) { - SetRateScaledImuResponse::MergeImpl(*this, from); - } + void MergeFrom( const SetRatePositionResponse& from) { + SetRatePositionResponse::MergeImpl(*this, from); + } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: @@ -18179,16 +18257,16 @@ class SetRateScaledImuResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateScaledImuResponse* other); + void InternalSwap(SetRatePositionResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateScaledImuResponse"; + return "mavsdk.rpc.telemetry.SetRatePositionResponse"; } protected: - explicit SetRateScaledImuResponse(::google::protobuf::Arena* arena); - SetRateScaledImuResponse(::google::protobuf::Arena* arena, const SetRateScaledImuResponse& from); + explicit SetRatePositionResponse(::google::protobuf::Arena* arena); + SetRatePositionResponse(::google::protobuf::Arena* arena, const SetRatePositionResponse& from); public: static const ClassData _class_data_; @@ -18218,7 +18296,7 @@ class SetRateScaledImuResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateScaledImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionResponse) private: class _Internal; @@ -18250,26 +18328,26 @@ class SetRateScaledImuResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateRcStatusResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRcStatusResponse) */ { +class SetRateOdometryResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateOdometryResponse) */ { public: - inline SetRateRcStatusResponse() : SetRateRcStatusResponse(nullptr) {} - ~SetRateRcStatusResponse() override; + inline SetRateOdometryResponse() : SetRateOdometryResponse(nullptr) {} + ~SetRateOdometryResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateRcStatusResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateOdometryResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateRcStatusResponse(const SetRateRcStatusResponse& from) - : SetRateRcStatusResponse(nullptr, from) {} - SetRateRcStatusResponse(SetRateRcStatusResponse&& from) noexcept - : SetRateRcStatusResponse() { + inline SetRateOdometryResponse(const SetRateOdometryResponse& from) + : SetRateOdometryResponse(nullptr, from) {} + SetRateOdometryResponse(SetRateOdometryResponse&& from) noexcept + : SetRateOdometryResponse() { *this = ::std::move(from); } - inline SetRateRcStatusResponse& operator=(const SetRateRcStatusResponse& from) { + inline SetRateOdometryResponse& operator=(const SetRateOdometryResponse& from) { CopyFrom(from); return *this; } - inline SetRateRcStatusResponse& operator=(SetRateRcStatusResponse&& from) noexcept { + inline SetRateOdometryResponse& operator=(SetRateOdometryResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -18301,20 +18379,20 @@ class SetRateRcStatusResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateRcStatusResponse& default_instance() { + static const SetRateOdometryResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateRcStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateRcStatusResponse_default_instance_); + static inline const SetRateOdometryResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateOdometryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 96; + 94; - friend void swap(SetRateRcStatusResponse& a, SetRateRcStatusResponse& b) { + friend void swap(SetRateOdometryResponse& a, SetRateOdometryResponse& b) { a.Swap(&b); } - inline void Swap(SetRateRcStatusResponse* other) { + inline void Swap(SetRateOdometryResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -18327,7 +18405,7 @@ class SetRateRcStatusResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateRcStatusResponse* other) { + void UnsafeArenaSwap(SetRateOdometryResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -18335,14 +18413,14 @@ class SetRateRcStatusResponse final : // implements Message ---------------------------------------------- - SetRateRcStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateOdometryResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateRcStatusResponse& from); + void CopyFrom(const SetRateOdometryResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateRcStatusResponse& from) { - SetRateRcStatusResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateOdometryResponse& from) { + SetRateOdometryResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -18360,16 +18438,16 @@ class SetRateRcStatusResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateRcStatusResponse* other); + void InternalSwap(SetRateOdometryResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateRcStatusResponse"; + return "mavsdk.rpc.telemetry.SetRateOdometryResponse"; } protected: - explicit SetRateRcStatusResponse(::google::protobuf::Arena* arena); - SetRateRcStatusResponse(::google::protobuf::Arena* arena, const SetRateRcStatusResponse& from); + explicit SetRateOdometryResponse(::google::protobuf::Arena* arena); + SetRateOdometryResponse(::google::protobuf::Arena* arena, const SetRateOdometryResponse& from); public: static const ClassData _class_data_; @@ -18399,7 +18477,7 @@ class SetRateRcStatusResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRcStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateOdometryResponse) private: class _Internal; @@ -18431,26 +18509,26 @@ class SetRateRcStatusResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateRawImuResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateRawImuResponse) */ { +class SetRateLandedStateResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateLandedStateResponse) */ { public: - inline SetRateRawImuResponse() : SetRateRawImuResponse(nullptr) {} - ~SetRateRawImuResponse() override; + inline SetRateLandedStateResponse() : SetRateLandedStateResponse(nullptr) {} + ~SetRateLandedStateResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateRawImuResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateLandedStateResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateRawImuResponse(const SetRateRawImuResponse& from) - : SetRateRawImuResponse(nullptr, from) {} - SetRateRawImuResponse(SetRateRawImuResponse&& from) noexcept - : SetRateRawImuResponse() { + inline SetRateLandedStateResponse(const SetRateLandedStateResponse& from) + : SetRateLandedStateResponse(nullptr, from) {} + SetRateLandedStateResponse(SetRateLandedStateResponse&& from) noexcept + : SetRateLandedStateResponse() { *this = ::std::move(from); } - inline SetRateRawImuResponse& operator=(const SetRateRawImuResponse& from) { + inline SetRateLandedStateResponse& operator=(const SetRateLandedStateResponse& from) { CopyFrom(from); return *this; } - inline SetRateRawImuResponse& operator=(SetRateRawImuResponse&& from) noexcept { + inline SetRateLandedStateResponse& operator=(SetRateLandedStateResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -18482,20 +18560,20 @@ class SetRateRawImuResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateRawImuResponse& default_instance() { + static const SetRateLandedStateResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateRawImuResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateRawImuResponse_default_instance_); + static inline const SetRateLandedStateResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateLandedStateResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 114; + 71; - friend void swap(SetRateRawImuResponse& a, SetRateRawImuResponse& b) { + friend void swap(SetRateLandedStateResponse& a, SetRateLandedStateResponse& b) { a.Swap(&b); } - inline void Swap(SetRateRawImuResponse* other) { + inline void Swap(SetRateLandedStateResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -18508,7 +18586,7 @@ class SetRateRawImuResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateRawImuResponse* other) { + void UnsafeArenaSwap(SetRateLandedStateResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -18516,14 +18594,14 @@ class SetRateRawImuResponse final : // implements Message ---------------------------------------------- - SetRateRawImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateLandedStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateRawImuResponse& from); + void CopyFrom(const SetRateLandedStateResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateRawImuResponse& from) { - SetRateRawImuResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateLandedStateResponse& from) { + SetRateLandedStateResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -18541,16 +18619,16 @@ class SetRateRawImuResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateRawImuResponse* other); + void InternalSwap(SetRateLandedStateResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateRawImuResponse"; + return "mavsdk.rpc.telemetry.SetRateLandedStateResponse"; } protected: - explicit SetRateRawImuResponse(::google::protobuf::Arena* arena); - SetRateRawImuResponse(::google::protobuf::Arena* arena, const SetRateRawImuResponse& from); + explicit SetRateLandedStateResponse(::google::protobuf::Arena* arena); + SetRateLandedStateResponse(::google::protobuf::Arena* arena, const SetRateLandedStateResponse& from); public: static const ClassData _class_data_; @@ -18580,7 +18658,7 @@ class SetRateRawImuResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateRawImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateLandedStateResponse) private: class _Internal; @@ -18612,26 +18690,26 @@ class SetRateRawImuResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRatePositionVelocityNedResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse) */ { +class SetRateInAirResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateInAirResponse) */ { public: - inline SetRatePositionVelocityNedResponse() : SetRatePositionVelocityNedResponse(nullptr) {} - ~SetRatePositionVelocityNedResponse() override; + inline SetRateInAirResponse() : SetRateInAirResponse(nullptr) {} + ~SetRateInAirResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRatePositionVelocityNedResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateInAirResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRatePositionVelocityNedResponse(const SetRatePositionVelocityNedResponse& from) - : SetRatePositionVelocityNedResponse(nullptr, from) {} - SetRatePositionVelocityNedResponse(SetRatePositionVelocityNedResponse&& from) noexcept - : SetRatePositionVelocityNedResponse() { + inline SetRateInAirResponse(const SetRateInAirResponse& from) + : SetRateInAirResponse(nullptr, from) {} + SetRateInAirResponse(SetRateInAirResponse&& from) noexcept + : SetRateInAirResponse() { *this = ::std::move(from); } - inline SetRatePositionVelocityNedResponse& operator=(const SetRatePositionVelocityNedResponse& from) { + inline SetRateInAirResponse& operator=(const SetRateInAirResponse& from) { CopyFrom(from); return *this; } - inline SetRatePositionVelocityNedResponse& operator=(SetRatePositionVelocityNedResponse&& from) noexcept { + inline SetRateInAirResponse& operator=(SetRateInAirResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -18663,20 +18741,20 @@ class SetRatePositionVelocityNedResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRatePositionVelocityNedResponse& default_instance() { + static const SetRateInAirResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRatePositionVelocityNedResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRatePositionVelocityNedResponse_default_instance_); + static inline const SetRateInAirResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateInAirResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 104; + 69; - friend void swap(SetRatePositionVelocityNedResponse& a, SetRatePositionVelocityNedResponse& b) { + friend void swap(SetRateInAirResponse& a, SetRateInAirResponse& b) { a.Swap(&b); } - inline void Swap(SetRatePositionVelocityNedResponse* other) { + inline void Swap(SetRateInAirResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -18689,7 +18767,7 @@ class SetRatePositionVelocityNedResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRatePositionVelocityNedResponse* other) { + void UnsafeArenaSwap(SetRateInAirResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -18697,14 +18775,14 @@ class SetRatePositionVelocityNedResponse final : // implements Message ---------------------------------------------- - SetRatePositionVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateInAirResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRatePositionVelocityNedResponse& from); + void CopyFrom(const SetRateInAirResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRatePositionVelocityNedResponse& from) { - SetRatePositionVelocityNedResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateInAirResponse& from) { + SetRateInAirResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -18722,16 +18800,16 @@ class SetRatePositionVelocityNedResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRatePositionVelocityNedResponse* other); + void InternalSwap(SetRateInAirResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse"; + return "mavsdk.rpc.telemetry.SetRateInAirResponse"; } protected: - explicit SetRatePositionVelocityNedResponse(::google::protobuf::Arena* arena); - SetRatePositionVelocityNedResponse(::google::protobuf::Arena* arena, const SetRatePositionVelocityNedResponse& from); + explicit SetRateInAirResponse(::google::protobuf::Arena* arena); + SetRateInAirResponse(::google::protobuf::Arena* arena, const SetRateInAirResponse& from); public: static const ClassData _class_data_; @@ -18761,7 +18839,7 @@ class SetRatePositionVelocityNedResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionVelocityNedResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateInAirResponse) private: class _Internal; @@ -18793,26 +18871,26 @@ class SetRatePositionVelocityNedResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRatePositionResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionResponse) */ { +class SetRateImuResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateImuResponse) */ { public: - inline SetRatePositionResponse() : SetRatePositionResponse(nullptr) {} - ~SetRatePositionResponse() override; + inline SetRateImuResponse() : SetRateImuResponse(nullptr) {} + ~SetRateImuResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRatePositionResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateImuResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRatePositionResponse(const SetRatePositionResponse& from) - : SetRatePositionResponse(nullptr, from) {} - SetRatePositionResponse(SetRatePositionResponse&& from) noexcept - : SetRatePositionResponse() { + inline SetRateImuResponse(const SetRateImuResponse& from) + : SetRateImuResponse(nullptr, from) {} + SetRateImuResponse(SetRateImuResponse&& from) noexcept + : SetRateImuResponse() { *this = ::std::move(from); } - inline SetRatePositionResponse& operator=(const SetRatePositionResponse& from) { + inline SetRateImuResponse& operator=(const SetRateImuResponse& from) { CopyFrom(from); return *this; } - inline SetRatePositionResponse& operator=(SetRatePositionResponse&& from) noexcept { + inline SetRateImuResponse& operator=(SetRateImuResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -18844,20 +18922,20 @@ class SetRatePositionResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRatePositionResponse& default_instance() { + static const SetRateImuResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRatePositionResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRatePositionResponse_default_instance_); + static inline const SetRateImuResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 69; + 102; - friend void swap(SetRatePositionResponse& a, SetRatePositionResponse& b) { + friend void swap(SetRateImuResponse& a, SetRateImuResponse& b) { a.Swap(&b); } - inline void Swap(SetRatePositionResponse* other) { + inline void Swap(SetRateImuResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -18870,7 +18948,7 @@ class SetRatePositionResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRatePositionResponse* other) { + void UnsafeArenaSwap(SetRateImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -18878,14 +18956,14 @@ class SetRatePositionResponse final : // implements Message ---------------------------------------------- - SetRatePositionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRatePositionResponse& from); + void CopyFrom(const SetRateImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRatePositionResponse& from) { - SetRatePositionResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateImuResponse& from) { + SetRateImuResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -18903,16 +18981,16 @@ class SetRatePositionResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRatePositionResponse* other); + void InternalSwap(SetRateImuResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRatePositionResponse"; + return "mavsdk.rpc.telemetry.SetRateImuResponse"; } protected: - explicit SetRatePositionResponse(::google::protobuf::Arena* arena); - SetRatePositionResponse(::google::protobuf::Arena* arena, const SetRatePositionResponse& from); + explicit SetRateImuResponse(::google::protobuf::Arena* arena); + SetRateImuResponse(::google::protobuf::Arena* arena, const SetRateImuResponse& from); public: static const ClassData _class_data_; @@ -18942,7 +19020,7 @@ class SetRatePositionResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRatePositionResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateImuResponse) private: class _Internal; @@ -18974,26 +19052,26 @@ class SetRatePositionResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateOdometryResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateOdometryResponse) */ { +class SetRateHomeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateHomeResponse) */ { public: - inline SetRateOdometryResponse() : SetRateOdometryResponse(nullptr) {} - ~SetRateOdometryResponse() override; + inline SetRateHomeResponse() : SetRateHomeResponse(nullptr) {} + ~SetRateHomeResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateOdometryResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateHomeResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateOdometryResponse(const SetRateOdometryResponse& from) - : SetRateOdometryResponse(nullptr, from) {} - SetRateOdometryResponse(SetRateOdometryResponse&& from) noexcept - : SetRateOdometryResponse() { + inline SetRateHomeResponse(const SetRateHomeResponse& from) + : SetRateHomeResponse(nullptr, from) {} + SetRateHomeResponse(SetRateHomeResponse&& from) noexcept + : SetRateHomeResponse() { *this = ::std::move(from); } - inline SetRateOdometryResponse& operator=(const SetRateOdometryResponse& from) { + inline SetRateHomeResponse& operator=(const SetRateHomeResponse& from) { CopyFrom(from); return *this; } - inline SetRateOdometryResponse& operator=(SetRateOdometryResponse&& from) noexcept { + inline SetRateHomeResponse& operator=(SetRateHomeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19025,20 +19103,20 @@ class SetRateOdometryResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateOdometryResponse& default_instance() { + static const SetRateHomeResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateOdometryResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateOdometryResponse_default_instance_); + static inline const SetRateHomeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateHomeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 102; + 67; - friend void swap(SetRateOdometryResponse& a, SetRateOdometryResponse& b) { + friend void swap(SetRateHomeResponse& a, SetRateHomeResponse& b) { a.Swap(&b); } - inline void Swap(SetRateOdometryResponse* other) { + inline void Swap(SetRateHomeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19051,7 +19129,7 @@ class SetRateOdometryResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateOdometryResponse* other) { + void UnsafeArenaSwap(SetRateHomeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19059,14 +19137,14 @@ class SetRateOdometryResponse final : // implements Message ---------------------------------------------- - SetRateOdometryResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateHomeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateOdometryResponse& from); + void CopyFrom(const SetRateHomeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateOdometryResponse& from) { - SetRateOdometryResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateHomeResponse& from) { + SetRateHomeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19084,16 +19162,16 @@ class SetRateOdometryResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateOdometryResponse* other); + void InternalSwap(SetRateHomeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateOdometryResponse"; + return "mavsdk.rpc.telemetry.SetRateHomeResponse"; } protected: - explicit SetRateOdometryResponse(::google::protobuf::Arena* arena); - SetRateOdometryResponse(::google::protobuf::Arena* arena, const SetRateOdometryResponse& from); + explicit SetRateHomeResponse(::google::protobuf::Arena* arena); + SetRateHomeResponse(::google::protobuf::Arena* arena, const SetRateHomeResponse& from); public: static const ClassData _class_data_; @@ -19123,7 +19201,7 @@ class SetRateOdometryResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateOdometryResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateHomeResponse) private: class _Internal; @@ -19155,26 +19233,26 @@ class SetRateOdometryResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateLandedStateResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateLandedStateResponse) */ { +class SetRateGroundTruthResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGroundTruthResponse) */ { public: - inline SetRateLandedStateResponse() : SetRateLandedStateResponse(nullptr) {} - ~SetRateLandedStateResponse() override; + inline SetRateGroundTruthResponse() : SetRateGroundTruthResponse(nullptr) {} + ~SetRateGroundTruthResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateLandedStateResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateGroundTruthResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateLandedStateResponse(const SetRateLandedStateResponse& from) - : SetRateLandedStateResponse(nullptr, from) {} - SetRateLandedStateResponse(SetRateLandedStateResponse&& from) noexcept - : SetRateLandedStateResponse() { + inline SetRateGroundTruthResponse(const SetRateGroundTruthResponse& from) + : SetRateGroundTruthResponse(nullptr, from) {} + SetRateGroundTruthResponse(SetRateGroundTruthResponse&& from) noexcept + : SetRateGroundTruthResponse() { *this = ::std::move(from); } - inline SetRateLandedStateResponse& operator=(const SetRateLandedStateResponse& from) { + inline SetRateGroundTruthResponse& operator=(const SetRateGroundTruthResponse& from) { CopyFrom(from); return *this; } - inline SetRateLandedStateResponse& operator=(SetRateLandedStateResponse&& from) noexcept { + inline SetRateGroundTruthResponse& operator=(SetRateGroundTruthResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19206,20 +19284,20 @@ class SetRateLandedStateResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateLandedStateResponse& default_instance() { + static const SetRateGroundTruthResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateLandedStateResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateLandedStateResponse_default_instance_); + static inline const SetRateGroundTruthResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateGroundTruthResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 75; + 98; - friend void swap(SetRateLandedStateResponse& a, SetRateLandedStateResponse& b) { + friend void swap(SetRateGroundTruthResponse& a, SetRateGroundTruthResponse& b) { a.Swap(&b); } - inline void Swap(SetRateLandedStateResponse* other) { + inline void Swap(SetRateGroundTruthResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19232,7 +19310,7 @@ class SetRateLandedStateResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateLandedStateResponse* other) { + void UnsafeArenaSwap(SetRateGroundTruthResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19240,14 +19318,14 @@ class SetRateLandedStateResponse final : // implements Message ---------------------------------------------- - SetRateLandedStateResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateGroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateLandedStateResponse& from); + void CopyFrom(const SetRateGroundTruthResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateLandedStateResponse& from) { - SetRateLandedStateResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateGroundTruthResponse& from) { + SetRateGroundTruthResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19265,16 +19343,16 @@ class SetRateLandedStateResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateLandedStateResponse* other); + void InternalSwap(SetRateGroundTruthResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateLandedStateResponse"; + return "mavsdk.rpc.telemetry.SetRateGroundTruthResponse"; } protected: - explicit SetRateLandedStateResponse(::google::protobuf::Arena* arena); - SetRateLandedStateResponse(::google::protobuf::Arena* arena, const SetRateLandedStateResponse& from); + explicit SetRateGroundTruthResponse(::google::protobuf::Arena* arena); + SetRateGroundTruthResponse(::google::protobuf::Arena* arena, const SetRateGroundTruthResponse& from); public: static const ClassData _class_data_; @@ -19304,7 +19382,7 @@ class SetRateLandedStateResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateLandedStateResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGroundTruthResponse) private: class _Internal; @@ -19336,26 +19414,26 @@ class SetRateLandedStateResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateInAirResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateInAirResponse) */ { +class SetRateGpsInfoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGpsInfoResponse) */ { public: - inline SetRateInAirResponse() : SetRateInAirResponse(nullptr) {} - ~SetRateInAirResponse() override; + inline SetRateGpsInfoResponse() : SetRateGpsInfoResponse(nullptr) {} + ~SetRateGpsInfoResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateInAirResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateGpsInfoResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateInAirResponse(const SetRateInAirResponse& from) - : SetRateInAirResponse(nullptr, from) {} - SetRateInAirResponse(SetRateInAirResponse&& from) noexcept - : SetRateInAirResponse() { + inline SetRateGpsInfoResponse(const SetRateGpsInfoResponse& from) + : SetRateGpsInfoResponse(nullptr, from) {} + SetRateGpsInfoResponse(SetRateGpsInfoResponse&& from) noexcept + : SetRateGpsInfoResponse() { *this = ::std::move(from); } - inline SetRateInAirResponse& operator=(const SetRateInAirResponse& from) { + inline SetRateGpsInfoResponse& operator=(const SetRateGpsInfoResponse& from) { CopyFrom(from); return *this; } - inline SetRateInAirResponse& operator=(SetRateInAirResponse&& from) noexcept { + inline SetRateGpsInfoResponse& operator=(SetRateGpsInfoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19387,20 +19465,20 @@ class SetRateInAirResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateInAirResponse& default_instance() { + static const SetRateGpsInfoResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateInAirResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateInAirResponse_default_instance_); + static inline const SetRateGpsInfoResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateGpsInfoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 73; + 83; - friend void swap(SetRateInAirResponse& a, SetRateInAirResponse& b) { + friend void swap(SetRateGpsInfoResponse& a, SetRateGpsInfoResponse& b) { a.Swap(&b); } - inline void Swap(SetRateInAirResponse* other) { + inline void Swap(SetRateGpsInfoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19413,7 +19491,7 @@ class SetRateInAirResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateInAirResponse* other) { + void UnsafeArenaSwap(SetRateGpsInfoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19421,14 +19499,14 @@ class SetRateInAirResponse final : // implements Message ---------------------------------------------- - SetRateInAirResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateGpsInfoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateInAirResponse& from); + void CopyFrom(const SetRateGpsInfoResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateInAirResponse& from) { - SetRateInAirResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateGpsInfoResponse& from) { + SetRateGpsInfoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19446,16 +19524,16 @@ class SetRateInAirResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateInAirResponse* other); + void InternalSwap(SetRateGpsInfoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateInAirResponse"; + return "mavsdk.rpc.telemetry.SetRateGpsInfoResponse"; } protected: - explicit SetRateInAirResponse(::google::protobuf::Arena* arena); - SetRateInAirResponse(::google::protobuf::Arena* arena, const SetRateInAirResponse& from); + explicit SetRateGpsInfoResponse(::google::protobuf::Arena* arena); + SetRateGpsInfoResponse(::google::protobuf::Arena* arena, const SetRateGpsInfoResponse& from); public: static const ClassData _class_data_; @@ -19485,7 +19563,7 @@ class SetRateInAirResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateInAirResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGpsInfoResponse) private: class _Internal; @@ -19517,26 +19595,26 @@ class SetRateInAirResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateImuResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateImuResponse) */ { +class SetRateFixedwingMetricsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse) */ { public: - inline SetRateImuResponse() : SetRateImuResponse(nullptr) {} - ~SetRateImuResponse() override; + inline SetRateFixedwingMetricsResponse() : SetRateFixedwingMetricsResponse(nullptr) {} + ~SetRateFixedwingMetricsResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateImuResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateFixedwingMetricsResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateImuResponse(const SetRateImuResponse& from) - : SetRateImuResponse(nullptr, from) {} - SetRateImuResponse(SetRateImuResponse&& from) noexcept - : SetRateImuResponse() { + inline SetRateFixedwingMetricsResponse(const SetRateFixedwingMetricsResponse& from) + : SetRateFixedwingMetricsResponse(nullptr, from) {} + SetRateFixedwingMetricsResponse(SetRateFixedwingMetricsResponse&& from) noexcept + : SetRateFixedwingMetricsResponse() { *this = ::std::move(from); } - inline SetRateImuResponse& operator=(const SetRateImuResponse& from) { + inline SetRateFixedwingMetricsResponse& operator=(const SetRateFixedwingMetricsResponse& from) { CopyFrom(from); return *this; } - inline SetRateImuResponse& operator=(SetRateImuResponse&& from) noexcept { + inline SetRateFixedwingMetricsResponse& operator=(SetRateFixedwingMetricsResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19568,20 +19646,20 @@ class SetRateImuResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateImuResponse& default_instance() { + static const SetRateFixedwingMetricsResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateImuResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateImuResponse_default_instance_); + static inline const SetRateFixedwingMetricsResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateFixedwingMetricsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 110; + 100; - friend void swap(SetRateImuResponse& a, SetRateImuResponse& b) { + friend void swap(SetRateFixedwingMetricsResponse& a, SetRateFixedwingMetricsResponse& b) { a.Swap(&b); } - inline void Swap(SetRateImuResponse* other) { + inline void Swap(SetRateFixedwingMetricsResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19594,7 +19672,7 @@ class SetRateImuResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateImuResponse* other) { + void UnsafeArenaSwap(SetRateFixedwingMetricsResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19602,14 +19680,14 @@ class SetRateImuResponse final : // implements Message ---------------------------------------------- - SetRateImuResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateFixedwingMetricsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateImuResponse& from); + void CopyFrom(const SetRateFixedwingMetricsResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateImuResponse& from) { - SetRateImuResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateFixedwingMetricsResponse& from) { + SetRateFixedwingMetricsResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19627,16 +19705,16 @@ class SetRateImuResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateImuResponse* other); + void InternalSwap(SetRateFixedwingMetricsResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateImuResponse"; + return "mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse"; } protected: - explicit SetRateImuResponse(::google::protobuf::Arena* arena); - SetRateImuResponse(::google::protobuf::Arena* arena, const SetRateImuResponse& from); + explicit SetRateFixedwingMetricsResponse(::google::protobuf::Arena* arena); + SetRateFixedwingMetricsResponse(::google::protobuf::Arena* arena, const SetRateFixedwingMetricsResponse& from); public: static const ClassData _class_data_; @@ -19666,7 +19744,7 @@ class SetRateImuResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse) private: class _Internal; @@ -19698,26 +19776,26 @@ class SetRateImuResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateHomeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateHomeResponse) */ { +class SetRateDistanceSensorResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateDistanceSensorResponse) */ { public: - inline SetRateHomeResponse() : SetRateHomeResponse(nullptr) {} - ~SetRateHomeResponse() override; + inline SetRateDistanceSensorResponse() : SetRateDistanceSensorResponse(nullptr) {} + ~SetRateDistanceSensorResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateHomeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateDistanceSensorResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateHomeResponse(const SetRateHomeResponse& from) - : SetRateHomeResponse(nullptr, from) {} - SetRateHomeResponse(SetRateHomeResponse&& from) noexcept - : SetRateHomeResponse() { + inline SetRateDistanceSensorResponse(const SetRateDistanceSensorResponse& from) + : SetRateDistanceSensorResponse(nullptr, from) {} + SetRateDistanceSensorResponse(SetRateDistanceSensorResponse&& from) noexcept + : SetRateDistanceSensorResponse() { *this = ::std::move(from); } - inline SetRateHomeResponse& operator=(const SetRateHomeResponse& from) { + inline SetRateDistanceSensorResponse& operator=(const SetRateDistanceSensorResponse& from) { CopyFrom(from); return *this; } - inline SetRateHomeResponse& operator=(SetRateHomeResponse&& from) noexcept { + inline SetRateDistanceSensorResponse& operator=(SetRateDistanceSensorResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19749,20 +19827,20 @@ class SetRateHomeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateHomeResponse& default_instance() { + static const SetRateDistanceSensorResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateHomeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateHomeResponse_default_instance_); + static inline const SetRateDistanceSensorResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateDistanceSensorResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 71; + 110; - friend void swap(SetRateHomeResponse& a, SetRateHomeResponse& b) { + friend void swap(SetRateDistanceSensorResponse& a, SetRateDistanceSensorResponse& b) { a.Swap(&b); } - inline void Swap(SetRateHomeResponse* other) { + inline void Swap(SetRateDistanceSensorResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19775,7 +19853,7 @@ class SetRateHomeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateHomeResponse* other) { + void UnsafeArenaSwap(SetRateDistanceSensorResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19783,14 +19861,14 @@ class SetRateHomeResponse final : // implements Message ---------------------------------------------- - SetRateHomeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateDistanceSensorResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateHomeResponse& from); + void CopyFrom(const SetRateDistanceSensorResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateHomeResponse& from) { - SetRateHomeResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateDistanceSensorResponse& from) { + SetRateDistanceSensorResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19808,16 +19886,16 @@ class SetRateHomeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateHomeResponse* other); + void InternalSwap(SetRateDistanceSensorResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateHomeResponse"; + return "mavsdk.rpc.telemetry.SetRateDistanceSensorResponse"; } protected: - explicit SetRateHomeResponse(::google::protobuf::Arena* arena); - SetRateHomeResponse(::google::protobuf::Arena* arena, const SetRateHomeResponse& from); + explicit SetRateDistanceSensorResponse(::google::protobuf::Arena* arena); + SetRateDistanceSensorResponse(::google::protobuf::Arena* arena, const SetRateDistanceSensorResponse& from); public: static const ClassData _class_data_; @@ -19847,7 +19925,7 @@ class SetRateHomeResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateHomeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateDistanceSensorResponse) private: class _Internal; @@ -19879,26 +19957,26 @@ class SetRateHomeResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateGroundTruthResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGroundTruthResponse) */ { +class SetRateBatteryResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateBatteryResponse) */ { public: - inline SetRateGroundTruthResponse() : SetRateGroundTruthResponse(nullptr) {} - ~SetRateGroundTruthResponse() override; + inline SetRateBatteryResponse() : SetRateBatteryResponse(nullptr) {} + ~SetRateBatteryResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateGroundTruthResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateBatteryResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateGroundTruthResponse(const SetRateGroundTruthResponse& from) - : SetRateGroundTruthResponse(nullptr, from) {} - SetRateGroundTruthResponse(SetRateGroundTruthResponse&& from) noexcept - : SetRateGroundTruthResponse() { + inline SetRateBatteryResponse(const SetRateBatteryResponse& from) + : SetRateBatteryResponse(nullptr, from) {} + SetRateBatteryResponse(SetRateBatteryResponse&& from) noexcept + : SetRateBatteryResponse() { *this = ::std::move(from); } - inline SetRateGroundTruthResponse& operator=(const SetRateGroundTruthResponse& from) { + inline SetRateBatteryResponse& operator=(const SetRateBatteryResponse& from) { CopyFrom(from); return *this; } - inline SetRateGroundTruthResponse& operator=(SetRateGroundTruthResponse&& from) noexcept { + inline SetRateBatteryResponse& operator=(SetRateBatteryResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -19930,20 +20008,20 @@ class SetRateGroundTruthResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateGroundTruthResponse& default_instance() { + static const SetRateBatteryResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateGroundTruthResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateGroundTruthResponse_default_instance_); + static inline const SetRateBatteryResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateBatteryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 106; + 86; - friend void swap(SetRateGroundTruthResponse& a, SetRateGroundTruthResponse& b) { + friend void swap(SetRateBatteryResponse& a, SetRateBatteryResponse& b) { a.Swap(&b); } - inline void Swap(SetRateGroundTruthResponse* other) { + inline void Swap(SetRateBatteryResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -19956,7 +20034,7 @@ class SetRateGroundTruthResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateGroundTruthResponse* other) { + void UnsafeArenaSwap(SetRateBatteryResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -19964,14 +20042,14 @@ class SetRateGroundTruthResponse final : // implements Message ---------------------------------------------- - SetRateGroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateBatteryResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateGroundTruthResponse& from); + void CopyFrom(const SetRateBatteryResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateGroundTruthResponse& from) { - SetRateGroundTruthResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateBatteryResponse& from) { + SetRateBatteryResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -19989,16 +20067,16 @@ class SetRateGroundTruthResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateGroundTruthResponse* other); + void InternalSwap(SetRateBatteryResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateGroundTruthResponse"; + return "mavsdk.rpc.telemetry.SetRateBatteryResponse"; } protected: - explicit SetRateGroundTruthResponse(::google::protobuf::Arena* arena); - SetRateGroundTruthResponse(::google::protobuf::Arena* arena, const SetRateGroundTruthResponse& from); + explicit SetRateBatteryResponse(::google::protobuf::Arena* arena); + SetRateBatteryResponse(::google::protobuf::Arena* arena, const SetRateBatteryResponse& from); public: static const ClassData _class_data_; @@ -20028,7 +20106,7 @@ class SetRateGroundTruthResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGroundTruthResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateBatteryResponse) private: class _Internal; @@ -20060,26 +20138,26 @@ class SetRateGroundTruthResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateGpsInfoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateGpsInfoResponse) */ { +class SetRateAttitudeQuaternionResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) */ { public: - inline SetRateGpsInfoResponse() : SetRateGpsInfoResponse(nullptr) {} - ~SetRateGpsInfoResponse() override; + inline SetRateAttitudeQuaternionResponse() : SetRateAttitudeQuaternionResponse(nullptr) {} + ~SetRateAttitudeQuaternionResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateGpsInfoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeQuaternionResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateGpsInfoResponse(const SetRateGpsInfoResponse& from) - : SetRateGpsInfoResponse(nullptr, from) {} - SetRateGpsInfoResponse(SetRateGpsInfoResponse&& from) noexcept - : SetRateGpsInfoResponse() { + inline SetRateAttitudeQuaternionResponse(const SetRateAttitudeQuaternionResponse& from) + : SetRateAttitudeQuaternionResponse(nullptr, from) {} + SetRateAttitudeQuaternionResponse(SetRateAttitudeQuaternionResponse&& from) noexcept + : SetRateAttitudeQuaternionResponse() { *this = ::std::move(from); } - inline SetRateGpsInfoResponse& operator=(const SetRateGpsInfoResponse& from) { + inline SetRateAttitudeQuaternionResponse& operator=(const SetRateAttitudeQuaternionResponse& from) { CopyFrom(from); return *this; } - inline SetRateGpsInfoResponse& operator=(SetRateGpsInfoResponse&& from) noexcept { + inline SetRateAttitudeQuaternionResponse& operator=(SetRateAttitudeQuaternionResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -20111,20 +20189,20 @@ class SetRateGpsInfoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateGpsInfoResponse& default_instance() { + static const SetRateAttitudeQuaternionResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateGpsInfoResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateGpsInfoResponse_default_instance_); + static inline const SetRateAttitudeQuaternionResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeQuaternionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 91; + 77; - friend void swap(SetRateGpsInfoResponse& a, SetRateGpsInfoResponse& b) { + friend void swap(SetRateAttitudeQuaternionResponse& a, SetRateAttitudeQuaternionResponse& b) { a.Swap(&b); } - inline void Swap(SetRateGpsInfoResponse* other) { + inline void Swap(SetRateAttitudeQuaternionResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -20137,7 +20215,7 @@ class SetRateGpsInfoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateGpsInfoResponse* other) { + void UnsafeArenaSwap(SetRateAttitudeQuaternionResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -20145,14 +20223,14 @@ class SetRateGpsInfoResponse final : // implements Message ---------------------------------------------- - SetRateGpsInfoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeQuaternionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateGpsInfoResponse& from); + void CopyFrom(const SetRateAttitudeQuaternionResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateGpsInfoResponse& from) { - SetRateGpsInfoResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeQuaternionResponse& from) { + SetRateAttitudeQuaternionResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -20170,16 +20248,16 @@ class SetRateGpsInfoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateGpsInfoResponse* other); + void InternalSwap(SetRateAttitudeQuaternionResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateGpsInfoResponse"; + return "mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse"; } protected: - explicit SetRateGpsInfoResponse(::google::protobuf::Arena* arena); - SetRateGpsInfoResponse(::google::protobuf::Arena* arena, const SetRateGpsInfoResponse& from); + explicit SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena); + SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionResponse& from); public: static const ClassData _class_data_; @@ -20209,7 +20287,7 @@ class SetRateGpsInfoResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateGpsInfoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) private: class _Internal; @@ -20241,26 +20319,26 @@ class SetRateGpsInfoResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateFixedwingMetricsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse) */ { +class SetRateAttitudeEulerResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) */ { public: - inline SetRateFixedwingMetricsResponse() : SetRateFixedwingMetricsResponse(nullptr) {} - ~SetRateFixedwingMetricsResponse() override; + inline SetRateAttitudeEulerResponse() : SetRateAttitudeEulerResponse(nullptr) {} + ~SetRateAttitudeEulerResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateFixedwingMetricsResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeEulerResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateFixedwingMetricsResponse(const SetRateFixedwingMetricsResponse& from) - : SetRateFixedwingMetricsResponse(nullptr, from) {} - SetRateFixedwingMetricsResponse(SetRateFixedwingMetricsResponse&& from) noexcept - : SetRateFixedwingMetricsResponse() { + inline SetRateAttitudeEulerResponse(const SetRateAttitudeEulerResponse& from) + : SetRateAttitudeEulerResponse(nullptr, from) {} + SetRateAttitudeEulerResponse(SetRateAttitudeEulerResponse&& from) noexcept + : SetRateAttitudeEulerResponse() { *this = ::std::move(from); } - inline SetRateFixedwingMetricsResponse& operator=(const SetRateFixedwingMetricsResponse& from) { + inline SetRateAttitudeEulerResponse& operator=(const SetRateAttitudeEulerResponse& from) { CopyFrom(from); return *this; } - inline SetRateFixedwingMetricsResponse& operator=(SetRateFixedwingMetricsResponse&& from) noexcept { + inline SetRateAttitudeEulerResponse& operator=(SetRateAttitudeEulerResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -20292,20 +20370,20 @@ class SetRateFixedwingMetricsResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateFixedwingMetricsResponse& default_instance() { + static const SetRateAttitudeEulerResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateFixedwingMetricsResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateFixedwingMetricsResponse_default_instance_); + static inline const SetRateAttitudeEulerResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeEulerResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 108; + 75; - friend void swap(SetRateFixedwingMetricsResponse& a, SetRateFixedwingMetricsResponse& b) { + friend void swap(SetRateAttitudeEulerResponse& a, SetRateAttitudeEulerResponse& b) { a.Swap(&b); } - inline void Swap(SetRateFixedwingMetricsResponse* other) { + inline void Swap(SetRateAttitudeEulerResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -20318,7 +20396,7 @@ class SetRateFixedwingMetricsResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateFixedwingMetricsResponse* other) { + void UnsafeArenaSwap(SetRateAttitudeEulerResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -20326,14 +20404,14 @@ class SetRateFixedwingMetricsResponse final : // implements Message ---------------------------------------------- - SetRateFixedwingMetricsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeEulerResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateFixedwingMetricsResponse& from); + void CopyFrom(const SetRateAttitudeEulerResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateFixedwingMetricsResponse& from) { - SetRateFixedwingMetricsResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeEulerResponse& from) { + SetRateAttitudeEulerResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -20351,16 +20429,16 @@ class SetRateFixedwingMetricsResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateFixedwingMetricsResponse* other); + void InternalSwap(SetRateAttitudeEulerResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse"; + return "mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse"; } protected: - explicit SetRateFixedwingMetricsResponse(::google::protobuf::Arena* arena); - SetRateFixedwingMetricsResponse(::google::protobuf::Arena* arena, const SetRateFixedwingMetricsResponse& from); + explicit SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena); + SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena, const SetRateAttitudeEulerResponse& from); public: static const ClassData _class_data_; @@ -20390,7 +20468,7 @@ class SetRateFixedwingMetricsResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateFixedwingMetricsResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) private: class _Internal; @@ -20422,26 +20500,26 @@ class SetRateFixedwingMetricsResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateDistanceSensorResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateDistanceSensorResponse) */ { +class SetRateAttitudeAngularVelocityBodyResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) */ { public: - inline SetRateDistanceSensorResponse() : SetRateDistanceSensorResponse(nullptr) {} - ~SetRateDistanceSensorResponse() override; + inline SetRateAttitudeAngularVelocityBodyResponse() : SetRateAttitudeAngularVelocityBodyResponse(nullptr) {} + ~SetRateAttitudeAngularVelocityBodyResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateDistanceSensorResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateDistanceSensorResponse(const SetRateDistanceSensorResponse& from) - : SetRateDistanceSensorResponse(nullptr, from) {} - SetRateDistanceSensorResponse(SetRateDistanceSensorResponse&& from) noexcept - : SetRateDistanceSensorResponse() { + inline SetRateAttitudeAngularVelocityBodyResponse(const SetRateAttitudeAngularVelocityBodyResponse& from) + : SetRateAttitudeAngularVelocityBodyResponse(nullptr, from) {} + SetRateAttitudeAngularVelocityBodyResponse(SetRateAttitudeAngularVelocityBodyResponse&& from) noexcept + : SetRateAttitudeAngularVelocityBodyResponse() { *this = ::std::move(from); } - inline SetRateDistanceSensorResponse& operator=(const SetRateDistanceSensorResponse& from) { + inline SetRateAttitudeAngularVelocityBodyResponse& operator=(const SetRateAttitudeAngularVelocityBodyResponse& from) { CopyFrom(from); return *this; } - inline SetRateDistanceSensorResponse& operator=(SetRateDistanceSensorResponse&& from) noexcept { + inline SetRateAttitudeAngularVelocityBodyResponse& operator=(SetRateAttitudeAngularVelocityBodyResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -20473,20 +20551,20 @@ class SetRateDistanceSensorResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateDistanceSensorResponse& default_instance() { + static const SetRateAttitudeAngularVelocityBodyResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateDistanceSensorResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateDistanceSensorResponse_default_instance_); + static inline const SetRateAttitudeAngularVelocityBodyResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateAttitudeAngularVelocityBodyResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 118; + 79; - friend void swap(SetRateDistanceSensorResponse& a, SetRateDistanceSensorResponse& b) { + friend void swap(SetRateAttitudeAngularVelocityBodyResponse& a, SetRateAttitudeAngularVelocityBodyResponse& b) { a.Swap(&b); } - inline void Swap(SetRateDistanceSensorResponse* other) { + inline void Swap(SetRateAttitudeAngularVelocityBodyResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -20499,7 +20577,7 @@ class SetRateDistanceSensorResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateDistanceSensorResponse* other) { + void UnsafeArenaSwap(SetRateAttitudeAngularVelocityBodyResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -20507,14 +20585,14 @@ class SetRateDistanceSensorResponse final : // implements Message ---------------------------------------------- - SetRateDistanceSensorResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAttitudeAngularVelocityBodyResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateDistanceSensorResponse& from); + void CopyFrom(const SetRateAttitudeAngularVelocityBodyResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateDistanceSensorResponse& from) { - SetRateDistanceSensorResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateAttitudeAngularVelocityBodyResponse& from) { + SetRateAttitudeAngularVelocityBodyResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -20532,16 +20610,16 @@ class SetRateDistanceSensorResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateDistanceSensorResponse* other); + void InternalSwap(SetRateAttitudeAngularVelocityBodyResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateDistanceSensorResponse"; + return "mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse"; } protected: - explicit SetRateDistanceSensorResponse(::google::protobuf::Arena* arena); - SetRateDistanceSensorResponse(::google::protobuf::Arena* arena, const SetRateDistanceSensorResponse& from); + explicit SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena); + SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyResponse& from); public: static const ClassData _class_data_; @@ -20571,7 +20649,7 @@ class SetRateDistanceSensorResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateDistanceSensorResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) private: class _Internal; @@ -20603,26 +20681,26 @@ class SetRateDistanceSensorResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateCameraAttitudeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) */ { - public: - inline SetRateCameraAttitudeResponse() : SetRateCameraAttitudeResponse(nullptr) {} - ~SetRateCameraAttitudeResponse() override; +class SetRateAltitudeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeResponse) */ { + public: + inline SetRateAltitudeResponse() : SetRateAltitudeResponse(nullptr) {} + ~SetRateAltitudeResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateCameraAttitudeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateAltitudeResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateCameraAttitudeResponse(const SetRateCameraAttitudeResponse& from) - : SetRateCameraAttitudeResponse(nullptr, from) {} - SetRateCameraAttitudeResponse(SetRateCameraAttitudeResponse&& from) noexcept - : SetRateCameraAttitudeResponse() { + inline SetRateAltitudeResponse(const SetRateAltitudeResponse& from) + : SetRateAltitudeResponse(nullptr, from) {} + SetRateAltitudeResponse(SetRateAltitudeResponse&& from) noexcept + : SetRateAltitudeResponse() { *this = ::std::move(from); } - inline SetRateCameraAttitudeResponse& operator=(const SetRateCameraAttitudeResponse& from) { + inline SetRateAltitudeResponse& operator=(const SetRateAltitudeResponse& from) { CopyFrom(from); return *this; } - inline SetRateCameraAttitudeResponse& operator=(SetRateCameraAttitudeResponse&& from) noexcept { + inline SetRateAltitudeResponse& operator=(SetRateAltitudeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -20654,20 +20732,20 @@ class SetRateCameraAttitudeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateCameraAttitudeResponse& default_instance() { + static const SetRateAltitudeResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateCameraAttitudeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateCameraAttitudeResponse_default_instance_); + static inline const SetRateAltitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateAltitudeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 87; + 114; - friend void swap(SetRateCameraAttitudeResponse& a, SetRateCameraAttitudeResponse& b) { + friend void swap(SetRateAltitudeResponse& a, SetRateAltitudeResponse& b) { a.Swap(&b); } - inline void Swap(SetRateCameraAttitudeResponse* other) { + inline void Swap(SetRateAltitudeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -20680,7 +20758,7 @@ class SetRateCameraAttitudeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateCameraAttitudeResponse* other) { + void UnsafeArenaSwap(SetRateAltitudeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -20688,14 +20766,14 @@ class SetRateCameraAttitudeResponse final : // implements Message ---------------------------------------------- - SetRateCameraAttitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAltitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateCameraAttitudeResponse& from); + void CopyFrom(const SetRateAltitudeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateCameraAttitudeResponse& from) { - SetRateCameraAttitudeResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateAltitudeResponse& from) { + SetRateAltitudeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -20713,16 +20791,16 @@ class SetRateCameraAttitudeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateCameraAttitudeResponse* other); + void InternalSwap(SetRateAltitudeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse"; + return "mavsdk.rpc.telemetry.SetRateAltitudeResponse"; } protected: - explicit SetRateCameraAttitudeResponse(::google::protobuf::Arena* arena); - SetRateCameraAttitudeResponse(::google::protobuf::Arena* arena, const SetRateCameraAttitudeResponse& from); + explicit SetRateAltitudeResponse(::google::protobuf::Arena* arena); + SetRateAltitudeResponse(::google::protobuf::Arena* arena, const SetRateAltitudeResponse& from); public: static const ClassData _class_data_; @@ -20752,7 +20830,7 @@ class SetRateCameraAttitudeResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAltitudeResponse) private: class _Internal; @@ -20784,26 +20862,26 @@ class SetRateCameraAttitudeResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateCameraAttitudeQuaternionResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) */ { +class SetRateActuatorOutputStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse) */ { public: - inline SetRateCameraAttitudeQuaternionResponse() : SetRateCameraAttitudeQuaternionResponse(nullptr) {} - ~SetRateCameraAttitudeQuaternionResponse() override; + inline SetRateActuatorOutputStatusResponse() : SetRateActuatorOutputStatusResponse(nullptr) {} + ~SetRateActuatorOutputStatusResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateCameraAttitudeQuaternionResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateActuatorOutputStatusResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateCameraAttitudeQuaternionResponse(const SetRateCameraAttitudeQuaternionResponse& from) - : SetRateCameraAttitudeQuaternionResponse(nullptr, from) {} - SetRateCameraAttitudeQuaternionResponse(SetRateCameraAttitudeQuaternionResponse&& from) noexcept - : SetRateCameraAttitudeQuaternionResponse() { + inline SetRateActuatorOutputStatusResponse(const SetRateActuatorOutputStatusResponse& from) + : SetRateActuatorOutputStatusResponse(nullptr, from) {} + SetRateActuatorOutputStatusResponse(SetRateActuatorOutputStatusResponse&& from) noexcept + : SetRateActuatorOutputStatusResponse() { *this = ::std::move(from); } - inline SetRateCameraAttitudeQuaternionResponse& operator=(const SetRateCameraAttitudeQuaternionResponse& from) { + inline SetRateActuatorOutputStatusResponse& operator=(const SetRateActuatorOutputStatusResponse& from) { CopyFrom(from); return *this; } - inline SetRateCameraAttitudeQuaternionResponse& operator=(SetRateCameraAttitudeQuaternionResponse&& from) noexcept { + inline SetRateActuatorOutputStatusResponse& operator=(SetRateActuatorOutputStatusResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -20835,20 +20913,20 @@ class SetRateCameraAttitudeQuaternionResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateCameraAttitudeQuaternionResponse& default_instance() { + static const SetRateActuatorOutputStatusResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateCameraAttitudeQuaternionResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateCameraAttitudeQuaternionResponse_default_instance_); + static inline const SetRateActuatorOutputStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateActuatorOutputStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 85; + 92; - friend void swap(SetRateCameraAttitudeQuaternionResponse& a, SetRateCameraAttitudeQuaternionResponse& b) { + friend void swap(SetRateActuatorOutputStatusResponse& a, SetRateActuatorOutputStatusResponse& b) { a.Swap(&b); } - inline void Swap(SetRateCameraAttitudeQuaternionResponse* other) { + inline void Swap(SetRateActuatorOutputStatusResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -20861,7 +20939,7 @@ class SetRateCameraAttitudeQuaternionResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateCameraAttitudeQuaternionResponse* other) { + void UnsafeArenaSwap(SetRateActuatorOutputStatusResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -20869,14 +20947,14 @@ class SetRateCameraAttitudeQuaternionResponse final : // implements Message ---------------------------------------------- - SetRateCameraAttitudeQuaternionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateActuatorOutputStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateCameraAttitudeQuaternionResponse& from); + void CopyFrom(const SetRateActuatorOutputStatusResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateCameraAttitudeQuaternionResponse& from) { - SetRateCameraAttitudeQuaternionResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateActuatorOutputStatusResponse& from) { + SetRateActuatorOutputStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -20894,16 +20972,16 @@ class SetRateCameraAttitudeQuaternionResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateCameraAttitudeQuaternionResponse* other); + void InternalSwap(SetRateActuatorOutputStatusResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse"; + return "mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse"; } protected: - explicit SetRateCameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena); - SetRateCameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena, const SetRateCameraAttitudeQuaternionResponse& from); + explicit SetRateActuatorOutputStatusResponse(::google::protobuf::Arena* arena); + SetRateActuatorOutputStatusResponse(::google::protobuf::Arena* arena, const SetRateActuatorOutputStatusResponse& from); public: static const ClassData _class_data_; @@ -20933,7 +21011,7 @@ class SetRateCameraAttitudeQuaternionResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse) private: class _Internal; @@ -20965,26 +21043,26 @@ class SetRateCameraAttitudeQuaternionResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateBatteryResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateBatteryResponse) */ { +class SetRateActuatorControlTargetResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse) */ { public: - inline SetRateBatteryResponse() : SetRateBatteryResponse(nullptr) {} - ~SetRateBatteryResponse() override; + inline SetRateActuatorControlTargetResponse() : SetRateActuatorControlTargetResponse(nullptr) {} + ~SetRateActuatorControlTargetResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateBatteryResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRateActuatorControlTargetResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateBatteryResponse(const SetRateBatteryResponse& from) - : SetRateBatteryResponse(nullptr, from) {} - SetRateBatteryResponse(SetRateBatteryResponse&& from) noexcept - : SetRateBatteryResponse() { + inline SetRateActuatorControlTargetResponse(const SetRateActuatorControlTargetResponse& from) + : SetRateActuatorControlTargetResponse(nullptr, from) {} + SetRateActuatorControlTargetResponse(SetRateActuatorControlTargetResponse&& from) noexcept + : SetRateActuatorControlTargetResponse() { *this = ::std::move(from); } - inline SetRateBatteryResponse& operator=(const SetRateBatteryResponse& from) { + inline SetRateActuatorControlTargetResponse& operator=(const SetRateActuatorControlTargetResponse& from) { CopyFrom(from); return *this; } - inline SetRateBatteryResponse& operator=(SetRateBatteryResponse&& from) noexcept { + inline SetRateActuatorControlTargetResponse& operator=(SetRateActuatorControlTargetResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21016,20 +21094,20 @@ class SetRateBatteryResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateBatteryResponse& default_instance() { + static const SetRateActuatorControlTargetResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateBatteryResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateBatteryResponse_default_instance_); + static inline const SetRateActuatorControlTargetResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateActuatorControlTargetResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 94; + 90; - friend void swap(SetRateBatteryResponse& a, SetRateBatteryResponse& b) { + friend void swap(SetRateActuatorControlTargetResponse& a, SetRateActuatorControlTargetResponse& b) { a.Swap(&b); } - inline void Swap(SetRateBatteryResponse* other) { + inline void Swap(SetRateActuatorControlTargetResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21042,7 +21120,7 @@ class SetRateBatteryResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateBatteryResponse* other) { + void UnsafeArenaSwap(SetRateActuatorControlTargetResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21050,14 +21128,14 @@ class SetRateBatteryResponse final : // implements Message ---------------------------------------------- - SetRateBatteryResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateActuatorControlTargetResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateBatteryResponse& from); + void CopyFrom(const SetRateActuatorControlTargetResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateBatteryResponse& from) { - SetRateBatteryResponse::MergeImpl(*this, from); + void MergeFrom( const SetRateActuatorControlTargetResponse& from) { + SetRateActuatorControlTargetResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21075,16 +21153,16 @@ class SetRateBatteryResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateBatteryResponse* other); + void InternalSwap(SetRateActuatorControlTargetResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateBatteryResponse"; + return "mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse"; } protected: - explicit SetRateBatteryResponse(::google::protobuf::Arena* arena); - SetRateBatteryResponse(::google::protobuf::Arena* arena, const SetRateBatteryResponse& from); + explicit SetRateActuatorControlTargetResponse(::google::protobuf::Arena* arena); + SetRateActuatorControlTargetResponse(::google::protobuf::Arena* arena, const SetRateActuatorControlTargetResponse& from); public: static const ClassData _class_data_; @@ -21114,7 +21192,7 @@ class SetRateBatteryResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateBatteryResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse) private: class _Internal; @@ -21146,26 +21224,26 @@ class SetRateBatteryResponse final : friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeQuaternionResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) */ { +class ScaledPressureResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ScaledPressureResponse) */ { public: - inline SetRateAttitudeQuaternionResponse() : SetRateAttitudeQuaternionResponse(nullptr) {} - ~SetRateAttitudeQuaternionResponse() override; + inline ScaledPressureResponse() : ScaledPressureResponse(nullptr) {} + ~ScaledPressureResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeQuaternionResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ScaledPressureResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeQuaternionResponse(const SetRateAttitudeQuaternionResponse& from) - : SetRateAttitudeQuaternionResponse(nullptr, from) {} - SetRateAttitudeQuaternionResponse(SetRateAttitudeQuaternionResponse&& from) noexcept - : SetRateAttitudeQuaternionResponse() { + inline ScaledPressureResponse(const ScaledPressureResponse& from) + : ScaledPressureResponse(nullptr, from) {} + ScaledPressureResponse(ScaledPressureResponse&& from) noexcept + : ScaledPressureResponse() { *this = ::std::move(from); } - inline SetRateAttitudeQuaternionResponse& operator=(const SetRateAttitudeQuaternionResponse& from) { + inline ScaledPressureResponse& operator=(const ScaledPressureResponse& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeQuaternionResponse& operator=(SetRateAttitudeQuaternionResponse&& from) noexcept { + inline ScaledPressureResponse& operator=(ScaledPressureResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21197,20 +21275,20 @@ class SetRateAttitudeQuaternionResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeQuaternionResponse& default_instance() { + static const ScaledPressureResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeQuaternionResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeQuaternionResponse_default_instance_); + static inline const ScaledPressureResponse* internal_default_instance() { + return reinterpret_cast( + &_ScaledPressureResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 81; + 59; - friend void swap(SetRateAttitudeQuaternionResponse& a, SetRateAttitudeQuaternionResponse& b) { + friend void swap(ScaledPressureResponse& a, ScaledPressureResponse& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeQuaternionResponse* other) { + inline void Swap(ScaledPressureResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21223,7 +21301,7 @@ class SetRateAttitudeQuaternionResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeQuaternionResponse* other) { + void UnsafeArenaSwap(ScaledPressureResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21231,14 +21309,14 @@ class SetRateAttitudeQuaternionResponse final : // implements Message ---------------------------------------------- - SetRateAttitudeQuaternionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ScaledPressureResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeQuaternionResponse& from); + void CopyFrom(const ScaledPressureResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeQuaternionResponse& from) { - SetRateAttitudeQuaternionResponse::MergeImpl(*this, from); + void MergeFrom( const ScaledPressureResponse& from) { + ScaledPressureResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21256,16 +21334,16 @@ class SetRateAttitudeQuaternionResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeQuaternionResponse* other); + void InternalSwap(ScaledPressureResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse"; + return "mavsdk.rpc.telemetry.ScaledPressureResponse"; } protected: - explicit SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena); - SetRateAttitudeQuaternionResponse(::google::protobuf::Arena* arena, const SetRateAttitudeQuaternionResponse& from); + explicit ScaledPressureResponse(::google::protobuf::Arena* arena); + ScaledPressureResponse(::google::protobuf::Arena* arena, const ScaledPressureResponse& from); public: static const ClassData _class_data_; @@ -21278,24 +21356,24 @@ class SetRateAttitudeQuaternionResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kScaledPressureFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; + bool has_scaled_pressure() const; + void clear_scaled_pressure() ; + const ::mavsdk::rpc::telemetry::ScaledPressure& scaled_pressure() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::ScaledPressure* release_scaled_pressure(); + ::mavsdk::rpc::telemetry::ScaledPressure* mutable_scaled_pressure(); + void set_allocated_scaled_pressure(::mavsdk::rpc::telemetry::ScaledPressure* value); + void unsafe_arena_set_allocated_scaled_pressure(::mavsdk::rpc::telemetry::ScaledPressure* value); + ::mavsdk::rpc::telemetry::ScaledPressure* unsafe_arena_release_scaled_pressure(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::ScaledPressure& _internal_scaled_pressure() const; + ::mavsdk::rpc::telemetry::ScaledPressure* _internal_mutable_scaled_pressure(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeQuaternionResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ScaledPressureResponse) private: class _Internal; @@ -21320,33 +21398,33 @@ class SetRateAttitudeQuaternionResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::ScaledPressure* scaled_pressure_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeEulerResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) */ { +class RcStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatusResponse) */ { public: - inline SetRateAttitudeEulerResponse() : SetRateAttitudeEulerResponse(nullptr) {} - ~SetRateAttitudeEulerResponse() override; + inline RcStatusResponse() : RcStatusResponse(nullptr) {} + ~RcStatusResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeEulerResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RcStatusResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeEulerResponse(const SetRateAttitudeEulerResponse& from) - : SetRateAttitudeEulerResponse(nullptr, from) {} - SetRateAttitudeEulerResponse(SetRateAttitudeEulerResponse&& from) noexcept - : SetRateAttitudeEulerResponse() { + inline RcStatusResponse(const RcStatusResponse& from) + : RcStatusResponse(nullptr, from) {} + RcStatusResponse(RcStatusResponse&& from) noexcept + : RcStatusResponse() { *this = ::std::move(from); } - inline SetRateAttitudeEulerResponse& operator=(const SetRateAttitudeEulerResponse& from) { + inline RcStatusResponse& operator=(const RcStatusResponse& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeEulerResponse& operator=(SetRateAttitudeEulerResponse&& from) noexcept { + inline RcStatusResponse& operator=(RcStatusResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21378,20 +21456,20 @@ class SetRateAttitudeEulerResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeEulerResponse& default_instance() { + static const RcStatusResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeEulerResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeEulerResponse_default_instance_); + static inline const RcStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_RcStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 79; + 31; - friend void swap(SetRateAttitudeEulerResponse& a, SetRateAttitudeEulerResponse& b) { + friend void swap(RcStatusResponse& a, RcStatusResponse& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeEulerResponse* other) { + inline void Swap(RcStatusResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21404,7 +21482,7 @@ class SetRateAttitudeEulerResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeEulerResponse* other) { + void UnsafeArenaSwap(RcStatusResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21412,14 +21490,14 @@ class SetRateAttitudeEulerResponse final : // implements Message ---------------------------------------------- - SetRateAttitudeEulerResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RcStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeEulerResponse& from); + void CopyFrom(const RcStatusResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeEulerResponse& from) { - SetRateAttitudeEulerResponse::MergeImpl(*this, from); + void MergeFrom( const RcStatusResponse& from) { + RcStatusResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21437,16 +21515,16 @@ class SetRateAttitudeEulerResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeEulerResponse* other); + void InternalSwap(RcStatusResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse"; + return "mavsdk.rpc.telemetry.RcStatusResponse"; } protected: - explicit SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena); - SetRateAttitudeEulerResponse(::google::protobuf::Arena* arena, const SetRateAttitudeEulerResponse& from); + explicit RcStatusResponse(::google::protobuf::Arena* arena); + RcStatusResponse(::google::protobuf::Arena* arena, const RcStatusResponse& from); public: static const ClassData _class_data_; @@ -21459,24 +21537,24 @@ class SetRateAttitudeEulerResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kRcStatusFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + bool has_rc_status() const; + void clear_rc_status() ; + const ::mavsdk::rpc::telemetry::RcStatus& rc_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::RcStatus* release_rc_status(); + ::mavsdk::rpc::telemetry::RcStatus* mutable_rc_status(); + void set_allocated_rc_status(::mavsdk::rpc::telemetry::RcStatus* value); + void unsafe_arena_set_allocated_rc_status(::mavsdk::rpc::telemetry::RcStatus* value); + ::mavsdk::rpc::telemetry::RcStatus* unsafe_arena_release_rc_status(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::RcStatus& _internal_rc_status() const; + ::mavsdk::rpc::telemetry::RcStatus* _internal_mutable_rc_status(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeEulerResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatusResponse) private: class _Internal; @@ -21501,33 +21579,33 @@ class SetRateAttitudeEulerResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::RcStatus* rc_status_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAttitudeAngularVelocityBodyResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) */ { +class RawGpsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RawGpsResponse) */ { public: - inline SetRateAttitudeAngularVelocityBodyResponse() : SetRateAttitudeAngularVelocityBodyResponse(nullptr) {} - ~SetRateAttitudeAngularVelocityBodyResponse() override; + inline RawGpsResponse() : RawGpsResponse(nullptr) {} + ~RawGpsResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR RawGpsResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateAttitudeAngularVelocityBodyResponse(const SetRateAttitudeAngularVelocityBodyResponse& from) - : SetRateAttitudeAngularVelocityBodyResponse(nullptr, from) {} - SetRateAttitudeAngularVelocityBodyResponse(SetRateAttitudeAngularVelocityBodyResponse&& from) noexcept - : SetRateAttitudeAngularVelocityBodyResponse() { + inline RawGpsResponse(const RawGpsResponse& from) + : RawGpsResponse(nullptr, from) {} + RawGpsResponse(RawGpsResponse&& from) noexcept + : RawGpsResponse() { *this = ::std::move(from); } - inline SetRateAttitudeAngularVelocityBodyResponse& operator=(const SetRateAttitudeAngularVelocityBodyResponse& from) { + inline RawGpsResponse& operator=(const RawGpsResponse& from) { CopyFrom(from); return *this; } - inline SetRateAttitudeAngularVelocityBodyResponse& operator=(SetRateAttitudeAngularVelocityBodyResponse&& from) noexcept { + inline RawGpsResponse& operator=(RawGpsResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21559,20 +21637,20 @@ class SetRateAttitudeAngularVelocityBodyResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAttitudeAngularVelocityBodyResponse& default_instance() { + static const RawGpsResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateAttitudeAngularVelocityBodyResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateAttitudeAngularVelocityBodyResponse_default_instance_); + static inline const RawGpsResponse* internal_default_instance() { + return reinterpret_cast( + &_RawGpsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 83; + 23; - friend void swap(SetRateAttitudeAngularVelocityBodyResponse& a, SetRateAttitudeAngularVelocityBodyResponse& b) { + friend void swap(RawGpsResponse& a, RawGpsResponse& b) { a.Swap(&b); } - inline void Swap(SetRateAttitudeAngularVelocityBodyResponse* other) { + inline void Swap(RawGpsResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21585,7 +21663,7 @@ class SetRateAttitudeAngularVelocityBodyResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAttitudeAngularVelocityBodyResponse* other) { + void UnsafeArenaSwap(RawGpsResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21593,14 +21671,14 @@ class SetRateAttitudeAngularVelocityBodyResponse final : // implements Message ---------------------------------------------- - SetRateAttitudeAngularVelocityBodyResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + RawGpsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAttitudeAngularVelocityBodyResponse& from); + void CopyFrom(const RawGpsResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAttitudeAngularVelocityBodyResponse& from) { - SetRateAttitudeAngularVelocityBodyResponse::MergeImpl(*this, from); + void MergeFrom( const RawGpsResponse& from) { + RawGpsResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21618,16 +21696,16 @@ class SetRateAttitudeAngularVelocityBodyResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAttitudeAngularVelocityBodyResponse* other); + void InternalSwap(RawGpsResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse"; + return "mavsdk.rpc.telemetry.RawGpsResponse"; } protected: - explicit SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena); - SetRateAttitudeAngularVelocityBodyResponse(::google::protobuf::Arena* arena, const SetRateAttitudeAngularVelocityBodyResponse& from); + explicit RawGpsResponse(::google::protobuf::Arena* arena); + RawGpsResponse(::google::protobuf::Arena* arena, const RawGpsResponse& from); public: static const ClassData _class_data_; @@ -21640,24 +21718,24 @@ class SetRateAttitudeAngularVelocityBodyResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kRawGpsFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; + bool has_raw_gps() const; + void clear_raw_gps() ; + const ::mavsdk::rpc::telemetry::RawGps& raw_gps() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::RawGps* release_raw_gps(); + ::mavsdk::rpc::telemetry::RawGps* mutable_raw_gps(); + void set_allocated_raw_gps(::mavsdk::rpc::telemetry::RawGps* value); + void unsafe_arena_set_allocated_raw_gps(::mavsdk::rpc::telemetry::RawGps* value); + ::mavsdk::rpc::telemetry::RawGps* unsafe_arena_release_raw_gps(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::RawGps& _internal_raw_gps() const; + ::mavsdk::rpc::telemetry::RawGps* _internal_mutable_raw_gps(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAttitudeAngularVelocityBodyResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RawGpsResponse) private: class _Internal; @@ -21682,33 +21760,33 @@ class SetRateAttitudeAngularVelocityBodyResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::RawGps* raw_gps_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateAltitudeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeResponse) */ { +class PositionVelocityNed final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionVelocityNed) */ { public: - inline SetRateAltitudeResponse() : SetRateAltitudeResponse(nullptr) {} - ~SetRateAltitudeResponse() override; + inline PositionVelocityNed() : PositionVelocityNed(nullptr) {} + ~PositionVelocityNed() override; template - explicit PROTOBUF_CONSTEXPR SetRateAltitudeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR PositionVelocityNed(::google::protobuf::internal::ConstantInitialized); - inline SetRateAltitudeResponse(const SetRateAltitudeResponse& from) - : SetRateAltitudeResponse(nullptr, from) {} - SetRateAltitudeResponse(SetRateAltitudeResponse&& from) noexcept - : SetRateAltitudeResponse() { + inline PositionVelocityNed(const PositionVelocityNed& from) + : PositionVelocityNed(nullptr, from) {} + PositionVelocityNed(PositionVelocityNed&& from) noexcept + : PositionVelocityNed() { *this = ::std::move(from); } - inline SetRateAltitudeResponse& operator=(const SetRateAltitudeResponse& from) { + inline PositionVelocityNed& operator=(const PositionVelocityNed& from) { CopyFrom(from); return *this; } - inline SetRateAltitudeResponse& operator=(SetRateAltitudeResponse&& from) noexcept { + inline PositionVelocityNed& operator=(PositionVelocityNed&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21740,20 +21818,20 @@ class SetRateAltitudeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateAltitudeResponse& default_instance() { + static const PositionVelocityNed& default_instance() { return *internal_default_instance(); } - static inline const SetRateAltitudeResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateAltitudeResponse_default_instance_); + static inline const PositionVelocityNed* internal_default_instance() { + return reinterpret_cast( + &_PositionVelocityNed_default_instance_); } static constexpr int kIndexInFileMessages = - 122; + 136; - friend void swap(SetRateAltitudeResponse& a, SetRateAltitudeResponse& b) { + friend void swap(PositionVelocityNed& a, PositionVelocityNed& b) { a.Swap(&b); } - inline void Swap(SetRateAltitudeResponse* other) { + inline void Swap(PositionVelocityNed* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21766,7 +21844,7 @@ class SetRateAltitudeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateAltitudeResponse* other) { + void UnsafeArenaSwap(PositionVelocityNed* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21774,14 +21852,14 @@ class SetRateAltitudeResponse final : // implements Message ---------------------------------------------- - SetRateAltitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + PositionVelocityNed* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateAltitudeResponse& from); + void CopyFrom(const PositionVelocityNed& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateAltitudeResponse& from) { - SetRateAltitudeResponse::MergeImpl(*this, from); + void MergeFrom( const PositionVelocityNed& from) { + PositionVelocityNed::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21799,16 +21877,16 @@ class SetRateAltitudeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateAltitudeResponse* other); + void InternalSwap(PositionVelocityNed* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateAltitudeResponse"; + return "mavsdk.rpc.telemetry.PositionVelocityNed"; } protected: - explicit SetRateAltitudeResponse(::google::protobuf::Arena* arena); - SetRateAltitudeResponse(::google::protobuf::Arena* arena, const SetRateAltitudeResponse& from); + explicit PositionVelocityNed(::google::protobuf::Arena* arena); + PositionVelocityNed(::google::protobuf::Arena* arena, const PositionVelocityNed& from); public: static const ClassData _class_data_; @@ -21821,30 +21899,46 @@ class SetRateAltitudeResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kPositionFieldNumber = 1, + kVelocityFieldNumber = 2, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.PositionNed position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::telemetry::PositionNed& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::PositionNed* release_position(); + ::mavsdk::rpc::telemetry::PositionNed* mutable_position(); + void set_allocated_position(::mavsdk::rpc::telemetry::PositionNed* value); + void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry::PositionNed* value); + ::mavsdk::rpc::telemetry::PositionNed* unsafe_arena_release_position(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::PositionNed& _internal_position() const; + ::mavsdk::rpc::telemetry::PositionNed* _internal_mutable_position(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + // .mavsdk.rpc.telemetry.VelocityNed velocity = 2; + bool has_velocity() const; + void clear_velocity() ; + const ::mavsdk::rpc::telemetry::VelocityNed& velocity() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityNed* release_velocity(); + ::mavsdk::rpc::telemetry::VelocityNed* mutable_velocity(); + void set_allocated_velocity(::mavsdk::rpc::telemetry::VelocityNed* value); + void unsafe_arena_set_allocated_velocity(::mavsdk::rpc::telemetry::VelocityNed* value); + ::mavsdk::rpc::telemetry::VelocityNed* unsafe_arena_release_velocity(); + + private: + const ::mavsdk::rpc::telemetry::VelocityNed& _internal_velocity() const; + ::mavsdk::rpc::telemetry::VelocityNed* _internal_mutable_velocity(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionVelocityNed) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 1, 2, 2, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -21863,33 +21957,34 @@ class SetRateAltitudeResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::PositionNed* position_; + ::mavsdk::rpc::telemetry::VelocityNed* velocity_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateActuatorOutputStatusResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse) */ { +class PositionResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionResponse) */ { public: - inline SetRateActuatorOutputStatusResponse() : SetRateActuatorOutputStatusResponse(nullptr) {} - ~SetRateActuatorOutputStatusResponse() override; + inline PositionResponse() : PositionResponse(nullptr) {} + ~PositionResponse() override; template - explicit PROTOBUF_CONSTEXPR SetRateActuatorOutputStatusResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR PositionResponse(::google::protobuf::internal::ConstantInitialized); - inline SetRateActuatorOutputStatusResponse(const SetRateActuatorOutputStatusResponse& from) - : SetRateActuatorOutputStatusResponse(nullptr, from) {} - SetRateActuatorOutputStatusResponse(SetRateActuatorOutputStatusResponse&& from) noexcept - : SetRateActuatorOutputStatusResponse() { + inline PositionResponse(const PositionResponse& from) + : PositionResponse(nullptr, from) {} + PositionResponse(PositionResponse&& from) noexcept + : PositionResponse() { *this = ::std::move(from); } - inline SetRateActuatorOutputStatusResponse& operator=(const SetRateActuatorOutputStatusResponse& from) { + inline PositionResponse& operator=(const PositionResponse& from) { CopyFrom(from); return *this; } - inline SetRateActuatorOutputStatusResponse& operator=(SetRateActuatorOutputStatusResponse&& from) noexcept { + inline PositionResponse& operator=(PositionResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -21921,20 +22016,20 @@ class SetRateActuatorOutputStatusResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateActuatorOutputStatusResponse& default_instance() { + static const PositionResponse& default_instance() { return *internal_default_instance(); } - static inline const SetRateActuatorOutputStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateActuatorOutputStatusResponse_default_instance_); + static inline const PositionResponse* internal_default_instance() { + return reinterpret_cast( + &_PositionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 100; + 1; - friend void swap(SetRateActuatorOutputStatusResponse& a, SetRateActuatorOutputStatusResponse& b) { + friend void swap(PositionResponse& a, PositionResponse& b) { a.Swap(&b); } - inline void Swap(SetRateActuatorOutputStatusResponse* other) { + inline void Swap(PositionResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -21947,7 +22042,7 @@ class SetRateActuatorOutputStatusResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateActuatorOutputStatusResponse* other) { + void UnsafeArenaSwap(PositionResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -21955,14 +22050,14 @@ class SetRateActuatorOutputStatusResponse final : // implements Message ---------------------------------------------- - SetRateActuatorOutputStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + PositionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateActuatorOutputStatusResponse& from); + void CopyFrom(const PositionResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateActuatorOutputStatusResponse& from) { - SetRateActuatorOutputStatusResponse::MergeImpl(*this, from); + void MergeFrom( const PositionResponse& from) { + PositionResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -21980,16 +22075,16 @@ class SetRateActuatorOutputStatusResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateActuatorOutputStatusResponse* other); + void InternalSwap(PositionResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse"; + return "mavsdk.rpc.telemetry.PositionResponse"; } protected: - explicit SetRateActuatorOutputStatusResponse(::google::protobuf::Arena* arena); - SetRateActuatorOutputStatusResponse(::google::protobuf::Arena* arena, const SetRateActuatorOutputStatusResponse& from); + explicit PositionResponse(::google::protobuf::Arena* arena); + PositionResponse(::google::protobuf::Arena* arena, const PositionResponse& from); public: static const ClassData _class_data_; @@ -22002,24 +22097,24 @@ class SetRateActuatorOutputStatusResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kPositionFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.Position position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::telemetry::Position& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Position* release_position(); + ::mavsdk::rpc::telemetry::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::telemetry::Position* value); + void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry::Position* value); + ::mavsdk::rpc::telemetry::Position* unsafe_arena_release_position(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::Position& _internal_position() const; + ::mavsdk::rpc::telemetry::Position* _internal_mutable_position(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorOutputStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionResponse) private: class _Internal; @@ -22044,33 +22139,33 @@ class SetRateActuatorOutputStatusResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::Position* position_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class SetRateActuatorControlTargetResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse) */ { +class Odometry final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Odometry) */ { public: - inline SetRateActuatorControlTargetResponse() : SetRateActuatorControlTargetResponse(nullptr) {} - ~SetRateActuatorControlTargetResponse() override; + inline Odometry() : Odometry(nullptr) {} + ~Odometry() override; template - explicit PROTOBUF_CONSTEXPR SetRateActuatorControlTargetResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Odometry(::google::protobuf::internal::ConstantInitialized); - inline SetRateActuatorControlTargetResponse(const SetRateActuatorControlTargetResponse& from) - : SetRateActuatorControlTargetResponse(nullptr, from) {} - SetRateActuatorControlTargetResponse(SetRateActuatorControlTargetResponse&& from) noexcept - : SetRateActuatorControlTargetResponse() { + inline Odometry(const Odometry& from) + : Odometry(nullptr, from) {} + Odometry(Odometry&& from) noexcept + : Odometry() { *this = ::std::move(from); } - inline SetRateActuatorControlTargetResponse& operator=(const SetRateActuatorControlTargetResponse& from) { + inline Odometry& operator=(const Odometry& from) { CopyFrom(from); return *this; } - inline SetRateActuatorControlTargetResponse& operator=(SetRateActuatorControlTargetResponse&& from) noexcept { + inline Odometry& operator=(Odometry&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -22102,20 +22197,20 @@ class SetRateActuatorControlTargetResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRateActuatorControlTargetResponse& default_instance() { + static const Odometry& default_instance() { return *internal_default_instance(); } - static inline const SetRateActuatorControlTargetResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRateActuatorControlTargetResponse_default_instance_); + static inline const Odometry* internal_default_instance() { + return reinterpret_cast( + &_Odometry_default_instance_); } static constexpr int kIndexInFileMessages = - 98; + 131; - friend void swap(SetRateActuatorControlTargetResponse& a, SetRateActuatorControlTargetResponse& b) { + friend void swap(Odometry& a, Odometry& b) { a.Swap(&b); } - inline void Swap(SetRateActuatorControlTargetResponse* other) { + inline void Swap(Odometry* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -22128,7 +22223,7 @@ class SetRateActuatorControlTargetResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRateActuatorControlTargetResponse* other) { + void UnsafeArenaSwap(Odometry* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -22136,14 +22231,14 @@ class SetRateActuatorControlTargetResponse final : // implements Message ---------------------------------------------- - SetRateActuatorControlTargetResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Odometry* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRateActuatorControlTargetResponse& from); + void CopyFrom(const Odometry& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRateActuatorControlTargetResponse& from) { - SetRateActuatorControlTargetResponse::MergeImpl(*this, from); + void MergeFrom( const Odometry& from) { + Odometry::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -22161,16 +22256,16 @@ class SetRateActuatorControlTargetResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRateActuatorControlTargetResponse* other); + void InternalSwap(Odometry* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse"; + return "mavsdk.rpc.telemetry.Odometry"; } protected: - explicit SetRateActuatorControlTargetResponse(::google::protobuf::Arena* arena); - SetRateActuatorControlTargetResponse(::google::protobuf::Arena* arena, const SetRateActuatorControlTargetResponse& from); + explicit Odometry(::google::protobuf::Arena* arena); + Odometry(::google::protobuf::Arena* arena, const Odometry& from); public: static const ClassData _class_data_; @@ -22180,214 +22275,168 @@ class SetRateActuatorControlTargetResponse final : // nested types ---------------------------------------------------- + using MavFrame = Odometry_MavFrame; + static constexpr MavFrame MAV_FRAME_UNDEF = Odometry_MavFrame_MAV_FRAME_UNDEF; + static constexpr MavFrame MAV_FRAME_BODY_NED = Odometry_MavFrame_MAV_FRAME_BODY_NED; + static constexpr MavFrame MAV_FRAME_VISION_NED = Odometry_MavFrame_MAV_FRAME_VISION_NED; + static constexpr MavFrame MAV_FRAME_ESTIM_NED = Odometry_MavFrame_MAV_FRAME_ESTIM_NED; + static inline bool MavFrame_IsValid(int value) { + return Odometry_MavFrame_IsValid(value); + } + static constexpr MavFrame MavFrame_MIN = Odometry_MavFrame_MavFrame_MIN; + static constexpr MavFrame MavFrame_MAX = Odometry_MavFrame_MavFrame_MAX; + static constexpr int MavFrame_ARRAYSIZE = Odometry_MavFrame_MavFrame_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* MavFrame_descriptor() { + return Odometry_MavFrame_descriptor(); + } + template + static inline const std::string& MavFrame_Name(T value) { + return Odometry_MavFrame_Name(value); + } + static inline bool MavFrame_Parse(absl::string_view name, MavFrame* value) { + return Odometry_MavFrame_Parse(name, value); + } + // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, + kPositionBodyFieldNumber = 4, + kQFieldNumber = 5, + kVelocityBodyFieldNumber = 6, + kAngularVelocityBodyFieldNumber = 7, + kPoseCovarianceFieldNumber = 8, + kVelocityCovarianceFieldNumber = 9, + kTimeUsecFieldNumber = 1, + kFrameIdFieldNumber = 2, + kChildFrameIdFieldNumber = 3, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + // .mavsdk.rpc.telemetry.PositionBody position_body = 4; + bool has_position_body() const; + void clear_position_body() ; + const ::mavsdk::rpc::telemetry::PositionBody& position_body() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::PositionBody* release_position_body(); + ::mavsdk::rpc::telemetry::PositionBody* mutable_position_body(); + void set_allocated_position_body(::mavsdk::rpc::telemetry::PositionBody* value); + void unsafe_arena_set_allocated_position_body(::mavsdk::rpc::telemetry::PositionBody* value); + ::mavsdk::rpc::telemetry::PositionBody* unsafe_arena_release_position_body(); private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + const ::mavsdk::rpc::telemetry::PositionBody& _internal_position_body() const; + ::mavsdk::rpc::telemetry::PositionBody* _internal_mutable_position_body(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateActuatorControlTargetResponse) - private: - class _Internal; + // .mavsdk.rpc.telemetry.Quaternion q = 5; + bool has_q() const; + void clear_q() ; + const ::mavsdk::rpc::telemetry::Quaternion& q() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Quaternion* release_q(); + ::mavsdk::rpc::telemetry::Quaternion* mutable_q(); + void set_allocated_q(::mavsdk::rpc::telemetry::Quaternion* value); + void unsafe_arena_set_allocated_q(::mavsdk::rpc::telemetry::Quaternion* value); + ::mavsdk::rpc::telemetry::Quaternion* unsafe_arena_release_q(); - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { + private: + const ::mavsdk::rpc::telemetry::Quaternion& _internal_q() const; + ::mavsdk::rpc::telemetry::Quaternion* _internal_mutable_q(); - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- + public: + // .mavsdk.rpc.telemetry.VelocityBody velocity_body = 6; + bool has_velocity_body() const; + void clear_velocity_body() ; + const ::mavsdk::rpc::telemetry::VelocityBody& velocity_body() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityBody* release_velocity_body(); + ::mavsdk::rpc::telemetry::VelocityBody* mutable_velocity_body(); + void set_allocated_velocity_body(::mavsdk::rpc::telemetry::VelocityBody* value); + void unsafe_arena_set_allocated_velocity_body(::mavsdk::rpc::telemetry::VelocityBody* value); + ::mavsdk::rpc::telemetry::VelocityBody* unsafe_arena_release_velocity_body(); -class ScaledPressureResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ScaledPressureResponse) */ { - public: - inline ScaledPressureResponse() : ScaledPressureResponse(nullptr) {} - ~ScaledPressureResponse() override; - template - explicit PROTOBUF_CONSTEXPR ScaledPressureResponse(::google::protobuf::internal::ConstantInitialized); + private: + const ::mavsdk::rpc::telemetry::VelocityBody& _internal_velocity_body() const; + ::mavsdk::rpc::telemetry::VelocityBody* _internal_mutable_velocity_body(); - inline ScaledPressureResponse(const ScaledPressureResponse& from) - : ScaledPressureResponse(nullptr, from) {} - ScaledPressureResponse(ScaledPressureResponse&& from) noexcept - : ScaledPressureResponse() { - *this = ::std::move(from); - } + public: + // .mavsdk.rpc.telemetry.AngularVelocityBody angular_velocity_body = 7; + bool has_angular_velocity_body() const; + void clear_angular_velocity_body() ; + const ::mavsdk::rpc::telemetry::AngularVelocityBody& angular_velocity_body() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AngularVelocityBody* release_angular_velocity_body(); + ::mavsdk::rpc::telemetry::AngularVelocityBody* mutable_angular_velocity_body(); + void set_allocated_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value); + void unsafe_arena_set_allocated_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value); + ::mavsdk::rpc::telemetry::AngularVelocityBody* unsafe_arena_release_angular_velocity_body(); - inline ScaledPressureResponse& operator=(const ScaledPressureResponse& from) { - CopyFrom(from); - return *this; - } - inline ScaledPressureResponse& operator=(ScaledPressureResponse&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } + private: + const ::mavsdk::rpc::telemetry::AngularVelocityBody& _internal_angular_velocity_body() const; + ::mavsdk::rpc::telemetry::AngularVelocityBody* _internal_mutable_angular_velocity_body(); - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const ScaledPressureResponse& default_instance() { - return *internal_default_instance(); - } - static inline const ScaledPressureResponse* internal_default_instance() { - return reinterpret_cast( - &_ScaledPressureResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 63; - - friend void swap(ScaledPressureResponse& a, ScaledPressureResponse& b) { - a.Swap(&b); - } - inline void Swap(ScaledPressureResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(ScaledPressureResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- + public: + // .mavsdk.rpc.telemetry.Covariance pose_covariance = 8; + bool has_pose_covariance() const; + void clear_pose_covariance() ; + const ::mavsdk::rpc::telemetry::Covariance& pose_covariance() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Covariance* release_pose_covariance(); + ::mavsdk::rpc::telemetry::Covariance* mutable_pose_covariance(); + void set_allocated_pose_covariance(::mavsdk::rpc::telemetry::Covariance* value); + void unsafe_arena_set_allocated_pose_covariance(::mavsdk::rpc::telemetry::Covariance* value); + ::mavsdk::rpc::telemetry::Covariance* unsafe_arena_release_pose_covariance(); - ScaledPressureResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ScaledPressureResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ScaledPressureResponse& from) { - ScaledPressureResponse::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; + const ::mavsdk::rpc::telemetry::Covariance& _internal_pose_covariance() const; + ::mavsdk::rpc::telemetry::Covariance* _internal_mutable_pose_covariance(); - ::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(); } + public: + // .mavsdk.rpc.telemetry.Covariance velocity_covariance = 9; + bool has_velocity_covariance() const; + void clear_velocity_covariance() ; + const ::mavsdk::rpc::telemetry::Covariance& velocity_covariance() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Covariance* release_velocity_covariance(); + ::mavsdk::rpc::telemetry::Covariance* mutable_velocity_covariance(); + void set_allocated_velocity_covariance(::mavsdk::rpc::telemetry::Covariance* value); + void unsafe_arena_set_allocated_velocity_covariance(::mavsdk::rpc::telemetry::Covariance* value); + ::mavsdk::rpc::telemetry::Covariance* unsafe_arena_release_velocity_covariance(); private: - ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; - void SharedCtor(::google::protobuf::Arena* arena); - void SharedDtor(); - void InternalSwap(ScaledPressureResponse* other); + const ::mavsdk::rpc::telemetry::Covariance& _internal_velocity_covariance() const; + ::mavsdk::rpc::telemetry::Covariance* _internal_mutable_velocity_covariance(); - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.ScaledPressureResponse"; - } - protected: - explicit ScaledPressureResponse(::google::protobuf::Arena* arena); - ScaledPressureResponse(::google::protobuf::Arena* arena, const ScaledPressureResponse& from); public: + // uint64 time_usec = 1; + void clear_time_usec() ; + ::uint64_t time_usec() const; + void set_time_usec(::uint64_t value); - static const ClassData _class_data_; - const ::google::protobuf::Message::ClassData*GetClassData() const final; - - ::google::protobuf::Metadata GetMetadata() const final; + private: + ::uint64_t _internal_time_usec() const; + void _internal_set_time_usec(::uint64_t value); - // nested types ---------------------------------------------------- + public: + // .mavsdk.rpc.telemetry.Odometry.MavFrame frame_id = 2; + void clear_frame_id() ; + ::mavsdk::rpc::telemetry::Odometry_MavFrame frame_id() const; + void set_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - // accessors ------------------------------------------------------- + private: + ::mavsdk::rpc::telemetry::Odometry_MavFrame _internal_frame_id() const; + void _internal_set_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - enum : int { - kScaledPressureFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.ScaledPressure scaled_pressure = 1; - bool has_scaled_pressure() const; - void clear_scaled_pressure() ; - const ::mavsdk::rpc::telemetry::ScaledPressure& scaled_pressure() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::ScaledPressure* release_scaled_pressure(); - ::mavsdk::rpc::telemetry::ScaledPressure* mutable_scaled_pressure(); - void set_allocated_scaled_pressure(::mavsdk::rpc::telemetry::ScaledPressure* value); - void unsafe_arena_set_allocated_scaled_pressure(::mavsdk::rpc::telemetry::ScaledPressure* value); - ::mavsdk::rpc::telemetry::ScaledPressure* unsafe_arena_release_scaled_pressure(); + public: + // .mavsdk.rpc.telemetry.Odometry.MavFrame child_frame_id = 3; + void clear_child_frame_id() ; + ::mavsdk::rpc::telemetry::Odometry_MavFrame child_frame_id() const; + void set_child_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); private: - const ::mavsdk::rpc::telemetry::ScaledPressure& _internal_scaled_pressure() const; - ::mavsdk::rpc::telemetry::ScaledPressure* _internal_mutable_scaled_pressure(); + ::mavsdk::rpc::telemetry::Odometry_MavFrame _internal_child_frame_id() const; + void _internal_set_child_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ScaledPressureResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Odometry) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 4, 9, 6, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -22406,33 +22455,41 @@ class ScaledPressureResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::ScaledPressure* scaled_pressure_; + ::mavsdk::rpc::telemetry::PositionBody* position_body_; + ::mavsdk::rpc::telemetry::Quaternion* q_; + ::mavsdk::rpc::telemetry::VelocityBody* velocity_body_; + ::mavsdk::rpc::telemetry::AngularVelocityBody* angular_velocity_body_; + ::mavsdk::rpc::telemetry::Covariance* pose_covariance_; + ::mavsdk::rpc::telemetry::Covariance* velocity_covariance_; + ::uint64_t time_usec_; + int frame_id_; + int child_frame_id_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class RcStatusResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatusResponse) */ { +class Imu final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Imu) */ { public: - inline RcStatusResponse() : RcStatusResponse(nullptr) {} - ~RcStatusResponse() override; + inline Imu() : Imu(nullptr) {} + ~Imu() override; template - explicit PROTOBUF_CONSTEXPR RcStatusResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR Imu(::google::protobuf::internal::ConstantInitialized); - inline RcStatusResponse(const RcStatusResponse& from) - : RcStatusResponse(nullptr, from) {} - RcStatusResponse(RcStatusResponse&& from) noexcept - : RcStatusResponse() { + inline Imu(const Imu& from) + : Imu(nullptr, from) {} + Imu(Imu&& from) noexcept + : Imu() { *this = ::std::move(from); } - inline RcStatusResponse& operator=(const RcStatusResponse& from) { + inline Imu& operator=(const Imu& from) { CopyFrom(from); return *this; } - inline RcStatusResponse& operator=(RcStatusResponse&& from) noexcept { + inline Imu& operator=(Imu&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -22464,20 +22521,20 @@ class RcStatusResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const RcStatusResponse& default_instance() { + static const Imu& default_instance() { return *internal_default_instance(); } - static inline const RcStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_RcStatusResponse_default_instance_); + static inline const Imu* internal_default_instance() { + return reinterpret_cast( + &_Imu_default_instance_); } static constexpr int kIndexInFileMessages = - 35; + 142; - friend void swap(RcStatusResponse& a, RcStatusResponse& b) { + friend void swap(Imu& a, Imu& b) { a.Swap(&b); } - inline void Swap(RcStatusResponse* other) { + inline void Swap(Imu* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -22490,7 +22547,7 @@ class RcStatusResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(RcStatusResponse* other) { + void UnsafeArenaSwap(Imu* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -22498,14 +22555,14 @@ class RcStatusResponse final : // implements Message ---------------------------------------------- - RcStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Imu* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RcStatusResponse& from); + void CopyFrom(const Imu& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RcStatusResponse& from) { - RcStatusResponse::MergeImpl(*this, from); + void MergeFrom( const Imu& from) { + Imu::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -22523,16 +22580,16 @@ class RcStatusResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(RcStatusResponse* other); + void InternalSwap(Imu* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.RcStatusResponse"; + return "mavsdk.rpc.telemetry.Imu"; } protected: - explicit RcStatusResponse(::google::protobuf::Arena* arena); - RcStatusResponse(::google::protobuf::Arena* arena, const RcStatusResponse& from); + explicit Imu(::google::protobuf::Arena* arena); + Imu(::google::protobuf::Arena* arena, const Imu& from); public: static const ClassData _class_data_; @@ -22545,1515 +22602,84 @@ class RcStatusResponse final : // accessors ------------------------------------------------------- enum : int { - kRcStatusFieldNumber = 1, + kAccelerationFrdFieldNumber = 1, + kAngularVelocityFrdFieldNumber = 2, + kMagneticFieldFrdFieldNumber = 3, + kTimestampUsFieldNumber = 5, + kTemperatureDegcFieldNumber = 4, }; - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; - bool has_rc_status() const; - void clear_rc_status() ; - const ::mavsdk::rpc::telemetry::RcStatus& rc_status() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::RcStatus* release_rc_status(); - ::mavsdk::rpc::telemetry::RcStatus* mutable_rc_status(); - void set_allocated_rc_status(::mavsdk::rpc::telemetry::RcStatus* value); - void unsafe_arena_set_allocated_rc_status(::mavsdk::rpc::telemetry::RcStatus* value); - ::mavsdk::rpc::telemetry::RcStatus* unsafe_arena_release_rc_status(); - - private: - const ::mavsdk::rpc::telemetry::RcStatus& _internal_rc_status() const; - ::mavsdk::rpc::telemetry::RcStatus* _internal_mutable_rc_status(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatusResponse) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::RcStatus* rc_status_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class RawGpsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RawGpsResponse) */ { - public: - inline RawGpsResponse() : RawGpsResponse(nullptr) {} - ~RawGpsResponse() override; - template - explicit PROTOBUF_CONSTEXPR RawGpsResponse(::google::protobuf::internal::ConstantInitialized); - - inline RawGpsResponse(const RawGpsResponse& from) - : RawGpsResponse(nullptr, from) {} - RawGpsResponse(RawGpsResponse&& from) noexcept - : RawGpsResponse() { - *this = ::std::move(from); - } - - inline RawGpsResponse& operator=(const RawGpsResponse& from) { - CopyFrom(from); - return *this; - } - inline RawGpsResponse& operator=(RawGpsResponse&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const RawGpsResponse& default_instance() { - return *internal_default_instance(); - } - static inline const RawGpsResponse* internal_default_instance() { - return reinterpret_cast( - &_RawGpsResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 27; - - friend void swap(RawGpsResponse& a, RawGpsResponse& b) { - a.Swap(&b); - } - inline void Swap(RawGpsResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(RawGpsResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - RawGpsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const RawGpsResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const RawGpsResponse& from) { - RawGpsResponse::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(RawGpsResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.RawGpsResponse"; - } - protected: - explicit RawGpsResponse(::google::protobuf::Arena* arena); - RawGpsResponse(::google::protobuf::Arena* arena, const RawGpsResponse& 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 { - kRawGpsFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.RawGps raw_gps = 1; - bool has_raw_gps() const; - void clear_raw_gps() ; - const ::mavsdk::rpc::telemetry::RawGps& raw_gps() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::RawGps* release_raw_gps(); - ::mavsdk::rpc::telemetry::RawGps* mutable_raw_gps(); - void set_allocated_raw_gps(::mavsdk::rpc::telemetry::RawGps* value); - void unsafe_arena_set_allocated_raw_gps(::mavsdk::rpc::telemetry::RawGps* value); - ::mavsdk::rpc::telemetry::RawGps* unsafe_arena_release_raw_gps(); - - private: - const ::mavsdk::rpc::telemetry::RawGps& _internal_raw_gps() const; - ::mavsdk::rpc::telemetry::RawGps* _internal_mutable_raw_gps(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RawGpsResponse) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::RawGps* raw_gps_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class PositionVelocityNed final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionVelocityNed) */ { - public: - inline PositionVelocityNed() : PositionVelocityNed(nullptr) {} - ~PositionVelocityNed() override; - template - explicit PROTOBUF_CONSTEXPR PositionVelocityNed(::google::protobuf::internal::ConstantInitialized); - - inline PositionVelocityNed(const PositionVelocityNed& from) - : PositionVelocityNed(nullptr, from) {} - PositionVelocityNed(PositionVelocityNed&& from) noexcept - : PositionVelocityNed() { - *this = ::std::move(from); - } - - inline PositionVelocityNed& operator=(const PositionVelocityNed& from) { - CopyFrom(from); - return *this; - } - inline PositionVelocityNed& operator=(PositionVelocityNed&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const PositionVelocityNed& default_instance() { - return *internal_default_instance(); - } - static inline const PositionVelocityNed* internal_default_instance() { - return reinterpret_cast( - &_PositionVelocityNed_default_instance_); - } - static constexpr int kIndexInFileMessages = - 144; - - friend void swap(PositionVelocityNed& a, PositionVelocityNed& b) { - a.Swap(&b); - } - inline void Swap(PositionVelocityNed* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(PositionVelocityNed* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - PositionVelocityNed* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PositionVelocityNed& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const PositionVelocityNed& from) { - PositionVelocityNed::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(PositionVelocityNed* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.PositionVelocityNed"; - } - protected: - explicit PositionVelocityNed(::google::protobuf::Arena* arena); - PositionVelocityNed(::google::protobuf::Arena* arena, const PositionVelocityNed& 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 { - kPositionFieldNumber = 1, - kVelocityFieldNumber = 2, - }; - // .mavsdk.rpc.telemetry.PositionNed position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::telemetry::PositionNed& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::PositionNed* release_position(); - ::mavsdk::rpc::telemetry::PositionNed* mutable_position(); - void set_allocated_position(::mavsdk::rpc::telemetry::PositionNed* value); - void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry::PositionNed* value); - ::mavsdk::rpc::telemetry::PositionNed* unsafe_arena_release_position(); - - private: - const ::mavsdk::rpc::telemetry::PositionNed& _internal_position() const; - ::mavsdk::rpc::telemetry::PositionNed* _internal_mutable_position(); - - public: - // .mavsdk.rpc.telemetry.VelocityNed velocity = 2; - bool has_velocity() const; - void clear_velocity() ; - const ::mavsdk::rpc::telemetry::VelocityNed& velocity() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityNed* release_velocity(); - ::mavsdk::rpc::telemetry::VelocityNed* mutable_velocity(); - void set_allocated_velocity(::mavsdk::rpc::telemetry::VelocityNed* value); - void unsafe_arena_set_allocated_velocity(::mavsdk::rpc::telemetry::VelocityNed* value); - ::mavsdk::rpc::telemetry::VelocityNed* unsafe_arena_release_velocity(); - - private: - const ::mavsdk::rpc::telemetry::VelocityNed& _internal_velocity() const; - ::mavsdk::rpc::telemetry::VelocityNed* _internal_mutable_velocity(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionVelocityNed) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 1, 2, 2, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::PositionNed* position_; - ::mavsdk::rpc::telemetry::VelocityNed* velocity_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class PositionResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.PositionResponse) */ { - public: - inline PositionResponse() : PositionResponse(nullptr) {} - ~PositionResponse() override; - template - explicit PROTOBUF_CONSTEXPR PositionResponse(::google::protobuf::internal::ConstantInitialized); - - inline PositionResponse(const PositionResponse& from) - : PositionResponse(nullptr, from) {} - PositionResponse(PositionResponse&& from) noexcept - : PositionResponse() { - *this = ::std::move(from); - } - - inline PositionResponse& operator=(const PositionResponse& from) { - CopyFrom(from); - return *this; - } - inline PositionResponse& operator=(PositionResponse&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const PositionResponse& default_instance() { - return *internal_default_instance(); - } - static inline const PositionResponse* internal_default_instance() { - return reinterpret_cast( - &_PositionResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 1; - - friend void swap(PositionResponse& a, PositionResponse& b) { - a.Swap(&b); - } - inline void Swap(PositionResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(PositionResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - PositionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PositionResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const PositionResponse& from) { - PositionResponse::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(PositionResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.PositionResponse"; - } - protected: - explicit PositionResponse(::google::protobuf::Arena* arena); - PositionResponse(::google::protobuf::Arena* arena, const PositionResponse& 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 { - kPositionFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.Position position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::telemetry::Position& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Position* release_position(); - ::mavsdk::rpc::telemetry::Position* mutable_position(); - void set_allocated_position(::mavsdk::rpc::telemetry::Position* value); - void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry::Position* value); - ::mavsdk::rpc::telemetry::Position* unsafe_arena_release_position(); - - private: - const ::mavsdk::rpc::telemetry::Position& _internal_position() const; - ::mavsdk::rpc::telemetry::Position* _internal_mutable_position(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.PositionResponse) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::Position* position_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class Odometry final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Odometry) */ { - public: - inline Odometry() : Odometry(nullptr) {} - ~Odometry() override; - template - explicit PROTOBUF_CONSTEXPR Odometry(::google::protobuf::internal::ConstantInitialized); - - inline Odometry(const Odometry& from) - : Odometry(nullptr, from) {} - Odometry(Odometry&& from) noexcept - : Odometry() { - *this = ::std::move(from); - } - - inline Odometry& operator=(const Odometry& from) { - CopyFrom(from); - return *this; - } - inline Odometry& operator=(Odometry&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const Odometry& default_instance() { - return *internal_default_instance(); - } - static inline const Odometry* internal_default_instance() { - return reinterpret_cast( - &_Odometry_default_instance_); - } - static constexpr int kIndexInFileMessages = - 139; - - friend void swap(Odometry& a, Odometry& b) { - a.Swap(&b); - } - inline void Swap(Odometry* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(Odometry* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - Odometry* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Odometry& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Odometry& from) { - Odometry::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(Odometry* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Odometry"; - } - protected: - explicit Odometry(::google::protobuf::Arena* arena); - Odometry(::google::protobuf::Arena* arena, const Odometry& from); - public: - - static const ClassData _class_data_; - const ::google::protobuf::Message::ClassData*GetClassData() const final; - - ::google::protobuf::Metadata GetMetadata() const final; - - // nested types ---------------------------------------------------- - - using MavFrame = Odometry_MavFrame; - static constexpr MavFrame MAV_FRAME_UNDEF = Odometry_MavFrame_MAV_FRAME_UNDEF; - static constexpr MavFrame MAV_FRAME_BODY_NED = Odometry_MavFrame_MAV_FRAME_BODY_NED; - static constexpr MavFrame MAV_FRAME_VISION_NED = Odometry_MavFrame_MAV_FRAME_VISION_NED; - static constexpr MavFrame MAV_FRAME_ESTIM_NED = Odometry_MavFrame_MAV_FRAME_ESTIM_NED; - static inline bool MavFrame_IsValid(int value) { - return Odometry_MavFrame_IsValid(value); - } - static constexpr MavFrame MavFrame_MIN = Odometry_MavFrame_MavFrame_MIN; - static constexpr MavFrame MavFrame_MAX = Odometry_MavFrame_MavFrame_MAX; - static constexpr int MavFrame_ARRAYSIZE = Odometry_MavFrame_MavFrame_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* MavFrame_descriptor() { - return Odometry_MavFrame_descriptor(); - } - template - static inline const std::string& MavFrame_Name(T value) { - return Odometry_MavFrame_Name(value); - } - static inline bool MavFrame_Parse(absl::string_view name, MavFrame* value) { - return Odometry_MavFrame_Parse(name, value); - } - - // accessors ------------------------------------------------------- - - enum : int { - kPositionBodyFieldNumber = 4, - kQFieldNumber = 5, - kVelocityBodyFieldNumber = 6, - kAngularVelocityBodyFieldNumber = 7, - kPoseCovarianceFieldNumber = 8, - kVelocityCovarianceFieldNumber = 9, - kTimeUsecFieldNumber = 1, - kFrameIdFieldNumber = 2, - kChildFrameIdFieldNumber = 3, - }; - // .mavsdk.rpc.telemetry.PositionBody position_body = 4; - bool has_position_body() const; - void clear_position_body() ; - const ::mavsdk::rpc::telemetry::PositionBody& position_body() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::PositionBody* release_position_body(); - ::mavsdk::rpc::telemetry::PositionBody* mutable_position_body(); - void set_allocated_position_body(::mavsdk::rpc::telemetry::PositionBody* value); - void unsafe_arena_set_allocated_position_body(::mavsdk::rpc::telemetry::PositionBody* value); - ::mavsdk::rpc::telemetry::PositionBody* unsafe_arena_release_position_body(); - - private: - const ::mavsdk::rpc::telemetry::PositionBody& _internal_position_body() const; - ::mavsdk::rpc::telemetry::PositionBody* _internal_mutable_position_body(); - - public: - // .mavsdk.rpc.telemetry.Quaternion q = 5; - bool has_q() const; - void clear_q() ; - const ::mavsdk::rpc::telemetry::Quaternion& q() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Quaternion* release_q(); - ::mavsdk::rpc::telemetry::Quaternion* mutable_q(); - void set_allocated_q(::mavsdk::rpc::telemetry::Quaternion* value); - void unsafe_arena_set_allocated_q(::mavsdk::rpc::telemetry::Quaternion* value); - ::mavsdk::rpc::telemetry::Quaternion* unsafe_arena_release_q(); - - private: - const ::mavsdk::rpc::telemetry::Quaternion& _internal_q() const; - ::mavsdk::rpc::telemetry::Quaternion* _internal_mutable_q(); - - public: - // .mavsdk.rpc.telemetry.VelocityBody velocity_body = 6; - bool has_velocity_body() const; - void clear_velocity_body() ; - const ::mavsdk::rpc::telemetry::VelocityBody& velocity_body() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::VelocityBody* release_velocity_body(); - ::mavsdk::rpc::telemetry::VelocityBody* mutable_velocity_body(); - void set_allocated_velocity_body(::mavsdk::rpc::telemetry::VelocityBody* value); - void unsafe_arena_set_allocated_velocity_body(::mavsdk::rpc::telemetry::VelocityBody* value); - ::mavsdk::rpc::telemetry::VelocityBody* unsafe_arena_release_velocity_body(); - - private: - const ::mavsdk::rpc::telemetry::VelocityBody& _internal_velocity_body() const; - ::mavsdk::rpc::telemetry::VelocityBody* _internal_mutable_velocity_body(); - - public: - // .mavsdk.rpc.telemetry.AngularVelocityBody angular_velocity_body = 7; - bool has_angular_velocity_body() const; - void clear_angular_velocity_body() ; - const ::mavsdk::rpc::telemetry::AngularVelocityBody& angular_velocity_body() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AngularVelocityBody* release_angular_velocity_body(); - ::mavsdk::rpc::telemetry::AngularVelocityBody* mutable_angular_velocity_body(); - void set_allocated_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value); - void unsafe_arena_set_allocated_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value); - ::mavsdk::rpc::telemetry::AngularVelocityBody* unsafe_arena_release_angular_velocity_body(); - - private: - const ::mavsdk::rpc::telemetry::AngularVelocityBody& _internal_angular_velocity_body() const; - ::mavsdk::rpc::telemetry::AngularVelocityBody* _internal_mutable_angular_velocity_body(); - - public: - // .mavsdk.rpc.telemetry.Covariance pose_covariance = 8; - bool has_pose_covariance() const; - void clear_pose_covariance() ; - const ::mavsdk::rpc::telemetry::Covariance& pose_covariance() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Covariance* release_pose_covariance(); - ::mavsdk::rpc::telemetry::Covariance* mutable_pose_covariance(); - void set_allocated_pose_covariance(::mavsdk::rpc::telemetry::Covariance* value); - void unsafe_arena_set_allocated_pose_covariance(::mavsdk::rpc::telemetry::Covariance* value); - ::mavsdk::rpc::telemetry::Covariance* unsafe_arena_release_pose_covariance(); - - private: - const ::mavsdk::rpc::telemetry::Covariance& _internal_pose_covariance() const; - ::mavsdk::rpc::telemetry::Covariance* _internal_mutable_pose_covariance(); - - public: - // .mavsdk.rpc.telemetry.Covariance velocity_covariance = 9; - bool has_velocity_covariance() const; - void clear_velocity_covariance() ; - const ::mavsdk::rpc::telemetry::Covariance& velocity_covariance() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Covariance* release_velocity_covariance(); - ::mavsdk::rpc::telemetry::Covariance* mutable_velocity_covariance(); - void set_allocated_velocity_covariance(::mavsdk::rpc::telemetry::Covariance* value); - void unsafe_arena_set_allocated_velocity_covariance(::mavsdk::rpc::telemetry::Covariance* value); - ::mavsdk::rpc::telemetry::Covariance* unsafe_arena_release_velocity_covariance(); - - private: - const ::mavsdk::rpc::telemetry::Covariance& _internal_velocity_covariance() const; - ::mavsdk::rpc::telemetry::Covariance* _internal_mutable_velocity_covariance(); - - public: - // uint64 time_usec = 1; - void clear_time_usec() ; - ::uint64_t time_usec() const; - void set_time_usec(::uint64_t value); - - private: - ::uint64_t _internal_time_usec() const; - void _internal_set_time_usec(::uint64_t value); - - public: - // .mavsdk.rpc.telemetry.Odometry.MavFrame frame_id = 2; - void clear_frame_id() ; - ::mavsdk::rpc::telemetry::Odometry_MavFrame frame_id() const; - void set_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - - private: - ::mavsdk::rpc::telemetry::Odometry_MavFrame _internal_frame_id() const; - void _internal_set_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - - public: - // .mavsdk.rpc.telemetry.Odometry.MavFrame child_frame_id = 3; - void clear_child_frame_id() ; - ::mavsdk::rpc::telemetry::Odometry_MavFrame child_frame_id() const; - void set_child_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - - private: - ::mavsdk::rpc::telemetry::Odometry_MavFrame _internal_child_frame_id() const; - void _internal_set_child_frame_id(::mavsdk::rpc::telemetry::Odometry_MavFrame value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Odometry) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 4, 9, 6, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::PositionBody* position_body_; - ::mavsdk::rpc::telemetry::Quaternion* q_; - ::mavsdk::rpc::telemetry::VelocityBody* velocity_body_; - ::mavsdk::rpc::telemetry::AngularVelocityBody* angular_velocity_body_; - ::mavsdk::rpc::telemetry::Covariance* pose_covariance_; - ::mavsdk::rpc::telemetry::Covariance* velocity_covariance_; - ::uint64_t time_usec_; - int frame_id_; - int child_frame_id_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class Imu final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Imu) */ { - public: - inline Imu() : Imu(nullptr) {} - ~Imu() override; - template - explicit PROTOBUF_CONSTEXPR Imu(::google::protobuf::internal::ConstantInitialized); - - inline Imu(const Imu& from) - : Imu(nullptr, from) {} - Imu(Imu&& from) noexcept - : Imu() { - *this = ::std::move(from); - } - - inline Imu& operator=(const Imu& from) { - CopyFrom(from); - return *this; - } - inline Imu& operator=(Imu&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const Imu& default_instance() { - return *internal_default_instance(); - } - static inline const Imu* internal_default_instance() { - return reinterpret_cast( - &_Imu_default_instance_); - } - static constexpr int kIndexInFileMessages = - 150; - - friend void swap(Imu& a, Imu& b) { - a.Swap(&b); - } - inline void Swap(Imu* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(Imu* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - Imu* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Imu& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Imu& from) { - Imu::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(Imu* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.Imu"; - } - protected: - explicit Imu(::google::protobuf::Arena* arena); - Imu(::google::protobuf::Arena* arena, const Imu& 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 { - kAccelerationFrdFieldNumber = 1, - kAngularVelocityFrdFieldNumber = 2, - kMagneticFieldFrdFieldNumber = 3, - kTimestampUsFieldNumber = 5, - kTemperatureDegcFieldNumber = 4, - }; - // .mavsdk.rpc.telemetry.AccelerationFrd acceleration_frd = 1; - bool has_acceleration_frd() const; - void clear_acceleration_frd() ; - const ::mavsdk::rpc::telemetry::AccelerationFrd& acceleration_frd() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AccelerationFrd* release_acceleration_frd(); - ::mavsdk::rpc::telemetry::AccelerationFrd* mutable_acceleration_frd(); - void set_allocated_acceleration_frd(::mavsdk::rpc::telemetry::AccelerationFrd* value); - void unsafe_arena_set_allocated_acceleration_frd(::mavsdk::rpc::telemetry::AccelerationFrd* value); - ::mavsdk::rpc::telemetry::AccelerationFrd* unsafe_arena_release_acceleration_frd(); - - private: - const ::mavsdk::rpc::telemetry::AccelerationFrd& _internal_acceleration_frd() const; - ::mavsdk::rpc::telemetry::AccelerationFrd* _internal_mutable_acceleration_frd(); - - public: - // .mavsdk.rpc.telemetry.AngularVelocityFrd angular_velocity_frd = 2; - bool has_angular_velocity_frd() const; - void clear_angular_velocity_frd() ; - const ::mavsdk::rpc::telemetry::AngularVelocityFrd& angular_velocity_frd() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AngularVelocityFrd* release_angular_velocity_frd(); - ::mavsdk::rpc::telemetry::AngularVelocityFrd* mutable_angular_velocity_frd(); - void set_allocated_angular_velocity_frd(::mavsdk::rpc::telemetry::AngularVelocityFrd* value); - void unsafe_arena_set_allocated_angular_velocity_frd(::mavsdk::rpc::telemetry::AngularVelocityFrd* value); - ::mavsdk::rpc::telemetry::AngularVelocityFrd* unsafe_arena_release_angular_velocity_frd(); - - private: - const ::mavsdk::rpc::telemetry::AngularVelocityFrd& _internal_angular_velocity_frd() const; - ::mavsdk::rpc::telemetry::AngularVelocityFrd* _internal_mutable_angular_velocity_frd(); - - public: - // .mavsdk.rpc.telemetry.MagneticFieldFrd magnetic_field_frd = 3; - bool has_magnetic_field_frd() const; - void clear_magnetic_field_frd() ; - const ::mavsdk::rpc::telemetry::MagneticFieldFrd& magnetic_field_frd() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::MagneticFieldFrd* release_magnetic_field_frd(); - ::mavsdk::rpc::telemetry::MagneticFieldFrd* mutable_magnetic_field_frd(); - void set_allocated_magnetic_field_frd(::mavsdk::rpc::telemetry::MagneticFieldFrd* value); - void unsafe_arena_set_allocated_magnetic_field_frd(::mavsdk::rpc::telemetry::MagneticFieldFrd* value); - ::mavsdk::rpc::telemetry::MagneticFieldFrd* unsafe_arena_release_magnetic_field_frd(); - - private: - const ::mavsdk::rpc::telemetry::MagneticFieldFrd& _internal_magnetic_field_frd() const; - ::mavsdk::rpc::telemetry::MagneticFieldFrd* _internal_mutable_magnetic_field_frd(); - - public: - // uint64 timestamp_us = 5; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); - - private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); - - public: - // float temperature_degc = 4 [(.mavsdk.options.default_value) = "NaN"]; - void clear_temperature_degc() ; - float temperature_degc() const; - void set_temperature_degc(float value); - - private: - float _internal_temperature_degc() const; - void _internal_set_temperature_degc(float value); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Imu) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 3, 5, 3, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::AccelerationFrd* acceleration_frd_; - ::mavsdk::rpc::telemetry::AngularVelocityFrd* angular_velocity_frd_; - ::mavsdk::rpc::telemetry::MagneticFieldFrd* magnetic_field_frd_; - ::uint64_t timestamp_us_; - float temperature_degc_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class HomeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HomeResponse) */ { - public: - inline HomeResponse() : HomeResponse(nullptr) {} - ~HomeResponse() override; - template - explicit PROTOBUF_CONSTEXPR HomeResponse(::google::protobuf::internal::ConstantInitialized); - - inline HomeResponse(const HomeResponse& from) - : HomeResponse(nullptr, from) {} - HomeResponse(HomeResponse&& from) noexcept - : HomeResponse() { - *this = ::std::move(from); - } - - inline HomeResponse& operator=(const HomeResponse& from) { - CopyFrom(from); - return *this; - } - inline HomeResponse& operator=(HomeResponse&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const HomeResponse& default_instance() { - return *internal_default_instance(); - } - static inline const HomeResponse* internal_default_instance() { - return reinterpret_cast( - &_HomeResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 3; - - friend void swap(HomeResponse& a, HomeResponse& b) { - a.Swap(&b); - } - inline void Swap(HomeResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(HomeResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - HomeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const HomeResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const HomeResponse& from) { - HomeResponse::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(HomeResponse* other); - - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.HomeResponse"; - } - protected: - explicit HomeResponse(::google::protobuf::Arena* arena); - HomeResponse(::google::protobuf::Arena* arena, const HomeResponse& 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 { - kHomeFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.Position home = 1; - bool has_home() const; - void clear_home() ; - const ::mavsdk::rpc::telemetry::Position& home() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Position* release_home(); - ::mavsdk::rpc::telemetry::Position* mutable_home(); - void set_allocated_home(::mavsdk::rpc::telemetry::Position* value); - void unsafe_arena_set_allocated_home(::mavsdk::rpc::telemetry::Position* value); - ::mavsdk::rpc::telemetry::Position* unsafe_arena_release_home(); - - private: - const ::mavsdk::rpc::telemetry::Position& _internal_home() const; - ::mavsdk::rpc::telemetry::Position* _internal_mutable_home(); - - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HomeResponse) - private: - class _Internal; - - friend class ::google::protobuf::internal::TcParser; - static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, - 0, 2> - _table_; - friend class ::google::protobuf::MessageLite; - friend class ::google::protobuf::Arena; - template - friend class ::google::protobuf::Arena::InternalHelper; - using InternalArenaConstructable_ = void; - using DestructorSkippable_ = void; - struct Impl_ { - - inline explicit constexpr Impl_( - ::google::protobuf::internal::ConstantInitialized) noexcept; - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena); - inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, - ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; - mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::Position* home_; - PROTOBUF_TSAN_DECLARE_MEMBER - }; - union { Impl_ _impl_; }; - friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; -};// ------------------------------------------------------------------- - -class HealthResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HealthResponse) */ { - public: - inline HealthResponse() : HealthResponse(nullptr) {} - ~HealthResponse() override; - template - explicit PROTOBUF_CONSTEXPR HealthResponse(::google::protobuf::internal::ConstantInitialized); - - inline HealthResponse(const HealthResponse& from) - : HealthResponse(nullptr, from) {} - HealthResponse(HealthResponse&& from) noexcept - : HealthResponse() { - *this = ::std::move(from); - } - - inline HealthResponse& operator=(const HealthResponse& from) { - CopyFrom(from); - return *this; - } - inline HealthResponse& operator=(HealthResponse&& from) noexcept { - if (this == &from) return *this; - if (GetArena() == from.GetArena() - #ifdef PROTOBUF_FORCE_COPY_IN_MOVE - && GetArena() != nullptr - #endif // !PROTOBUF_FORCE_COPY_IN_MOVE - ) { - InternalSwap(&from); - } else { - CopyFrom(from); - } - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); - } - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() - ABSL_ATTRIBUTE_LIFETIME_BOUND { - return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); - } - - static const ::google::protobuf::Descriptor* descriptor() { - return GetDescriptor(); - } - static const ::google::protobuf::Descriptor* GetDescriptor() { - return default_instance().GetMetadata().descriptor; - } - static const ::google::protobuf::Reflection* GetReflection() { - return default_instance().GetMetadata().reflection; - } - static const HealthResponse& default_instance() { - return *internal_default_instance(); - } - static inline const HealthResponse* internal_default_instance() { - return reinterpret_cast( - &_HealthResponse_default_instance_); - } - static constexpr int kIndexInFileMessages = - 33; - - friend void swap(HealthResponse& a, HealthResponse& b) { - a.Swap(&b); - } - inline void Swap(HealthResponse* other) { - if (other == this) return; - #ifdef PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() != nullptr && - GetArena() == other->GetArena()) { - #else // PROTOBUF_FORCE_COPY_IN_SWAP - if (GetArena() == other->GetArena()) { - #endif // !PROTOBUF_FORCE_COPY_IN_SWAP - InternalSwap(other); - } else { - ::google::protobuf::internal::GenericSwap(this, other); - } - } - void UnsafeArenaSwap(HealthResponse* other) { - if (other == this) return; - ABSL_DCHECK(GetArena() == other->GetArena()); - InternalSwap(other); - } - - // implements Message ---------------------------------------------- - - HealthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); - } - using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const HealthResponse& from); - using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const HealthResponse& from) { - HealthResponse::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(); } + // .mavsdk.rpc.telemetry.AccelerationFrd acceleration_frd = 1; + bool has_acceleration_frd() const; + void clear_acceleration_frd() ; + const ::mavsdk::rpc::telemetry::AccelerationFrd& acceleration_frd() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AccelerationFrd* release_acceleration_frd(); + ::mavsdk::rpc::telemetry::AccelerationFrd* mutable_acceleration_frd(); + void set_allocated_acceleration_frd(::mavsdk::rpc::telemetry::AccelerationFrd* value); + void unsafe_arena_set_allocated_acceleration_frd(::mavsdk::rpc::telemetry::AccelerationFrd* value); + ::mavsdk::rpc::telemetry::AccelerationFrd* unsafe_arena_release_acceleration_frd(); private: - ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; - void SharedCtor(::google::protobuf::Arena* arena); - void SharedDtor(); - void InternalSwap(HealthResponse* other); + const ::mavsdk::rpc::telemetry::AccelerationFrd& _internal_acceleration_frd() const; + ::mavsdk::rpc::telemetry::AccelerationFrd* _internal_mutable_acceleration_frd(); - private: - friend class ::google::protobuf::internal::AnyMetadata; - static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.HealthResponse"; - } - protected: - explicit HealthResponse(::google::protobuf::Arena* arena); - HealthResponse(::google::protobuf::Arena* arena, const HealthResponse& from); public: + // .mavsdk.rpc.telemetry.AngularVelocityFrd angular_velocity_frd = 2; + bool has_angular_velocity_frd() const; + void clear_angular_velocity_frd() ; + const ::mavsdk::rpc::telemetry::AngularVelocityFrd& angular_velocity_frd() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::AngularVelocityFrd* release_angular_velocity_frd(); + ::mavsdk::rpc::telemetry::AngularVelocityFrd* mutable_angular_velocity_frd(); + void set_allocated_angular_velocity_frd(::mavsdk::rpc::telemetry::AngularVelocityFrd* value); + void unsafe_arena_set_allocated_angular_velocity_frd(::mavsdk::rpc::telemetry::AngularVelocityFrd* value); + ::mavsdk::rpc::telemetry::AngularVelocityFrd* unsafe_arena_release_angular_velocity_frd(); - static const ClassData _class_data_; - const ::google::protobuf::Message::ClassData*GetClassData() const final; + private: + const ::mavsdk::rpc::telemetry::AngularVelocityFrd& _internal_angular_velocity_frd() const; + ::mavsdk::rpc::telemetry::AngularVelocityFrd* _internal_mutable_angular_velocity_frd(); - ::google::protobuf::Metadata GetMetadata() const final; + public: + // .mavsdk.rpc.telemetry.MagneticFieldFrd magnetic_field_frd = 3; + bool has_magnetic_field_frd() const; + void clear_magnetic_field_frd() ; + const ::mavsdk::rpc::telemetry::MagneticFieldFrd& magnetic_field_frd() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::MagneticFieldFrd* release_magnetic_field_frd(); + ::mavsdk::rpc::telemetry::MagneticFieldFrd* mutable_magnetic_field_frd(); + void set_allocated_magnetic_field_frd(::mavsdk::rpc::telemetry::MagneticFieldFrd* value); + void unsafe_arena_set_allocated_magnetic_field_frd(::mavsdk::rpc::telemetry::MagneticFieldFrd* value); + ::mavsdk::rpc::telemetry::MagneticFieldFrd* unsafe_arena_release_magnetic_field_frd(); - // nested types ---------------------------------------------------- + private: + const ::mavsdk::rpc::telemetry::MagneticFieldFrd& _internal_magnetic_field_frd() const; + ::mavsdk::rpc::telemetry::MagneticFieldFrd* _internal_mutable_magnetic_field_frd(); - // accessors ------------------------------------------------------- + public: + // uint64 timestamp_us = 5; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); - enum : int { - kHealthFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.Health health = 1; - bool has_health() const; - void clear_health() ; - const ::mavsdk::rpc::telemetry::Health& health() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Health* release_health(); - ::mavsdk::rpc::telemetry::Health* mutable_health(); - void set_allocated_health(::mavsdk::rpc::telemetry::Health* value); - void unsafe_arena_set_allocated_health(::mavsdk::rpc::telemetry::Health* value); - ::mavsdk::rpc::telemetry::Health* unsafe_arena_release_health(); + private: + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); + + public: + // float temperature_degc = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_temperature_degc() ; + float temperature_degc() const; + void set_temperature_degc(float value); private: - const ::mavsdk::rpc::telemetry::Health& _internal_health() const; - ::mavsdk::rpc::telemetry::Health* _internal_mutable_health(); + float _internal_temperature_degc() const; + void _internal_set_temperature_degc(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Imu) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 3, 5, 3, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -24072,33 +22698,37 @@ class HealthResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::Health* health_; + ::mavsdk::rpc::telemetry::AccelerationFrd* acceleration_frd_; + ::mavsdk::rpc::telemetry::AngularVelocityFrd* angular_velocity_frd_; + ::mavsdk::rpc::telemetry::MagneticFieldFrd* magnetic_field_frd_; + ::uint64_t timestamp_us_; + float temperature_degc_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class HeadingResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HeadingResponse) */ { +class HomeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HomeResponse) */ { public: - inline HeadingResponse() : HeadingResponse(nullptr) {} - ~HeadingResponse() override; + inline HomeResponse() : HomeResponse(nullptr) {} + ~HomeResponse() override; template - explicit PROTOBUF_CONSTEXPR HeadingResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR HomeResponse(::google::protobuf::internal::ConstantInitialized); - inline HeadingResponse(const HeadingResponse& from) - : HeadingResponse(nullptr, from) {} - HeadingResponse(HeadingResponse&& from) noexcept - : HeadingResponse() { + inline HomeResponse(const HomeResponse& from) + : HomeResponse(nullptr, from) {} + HomeResponse(HomeResponse&& from) noexcept + : HomeResponse() { *this = ::std::move(from); } - inline HeadingResponse& operator=(const HeadingResponse& from) { + inline HomeResponse& operator=(const HomeResponse& from) { CopyFrom(from); return *this; } - inline HeadingResponse& operator=(HeadingResponse&& from) noexcept { + inline HomeResponse& operator=(HomeResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -24130,20 +22760,20 @@ class HeadingResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const HeadingResponse& default_instance() { + static const HomeResponse& default_instance() { return *internal_default_instance(); } - static inline const HeadingResponse* internal_default_instance() { - return reinterpret_cast( - &_HeadingResponse_default_instance_); + static inline const HomeResponse* internal_default_instance() { + return reinterpret_cast( + &_HomeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 65; + 3; - friend void swap(HeadingResponse& a, HeadingResponse& b) { + friend void swap(HomeResponse& a, HomeResponse& b) { a.Swap(&b); } - inline void Swap(HeadingResponse* other) { + inline void Swap(HomeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -24156,7 +22786,7 @@ class HeadingResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(HeadingResponse* other) { + void UnsafeArenaSwap(HomeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -24164,14 +22794,14 @@ class HeadingResponse final : // implements Message ---------------------------------------------- - HeadingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + HomeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const HeadingResponse& from); + void CopyFrom(const HomeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const HeadingResponse& from) { - HeadingResponse::MergeImpl(*this, from); + void MergeFrom( const HomeResponse& from) { + HomeResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -24189,16 +22819,16 @@ class HeadingResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(HeadingResponse* other); + void InternalSwap(HomeResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.HeadingResponse"; + return "mavsdk.rpc.telemetry.HomeResponse"; } protected: - explicit HeadingResponse(::google::protobuf::Arena* arena); - HeadingResponse(::google::protobuf::Arena* arena, const HeadingResponse& from); + explicit HomeResponse(::google::protobuf::Arena* arena); + HomeResponse(::google::protobuf::Arena* arena, const HomeResponse& from); public: static const ClassData _class_data_; @@ -24211,24 +22841,24 @@ class HeadingResponse final : // accessors ------------------------------------------------------- enum : int { - kHeadingDegFieldNumber = 1, + kHomeFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.Heading heading_deg = 1; - bool has_heading_deg() const; - void clear_heading_deg() ; - const ::mavsdk::rpc::telemetry::Heading& heading_deg() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Heading* release_heading_deg(); - ::mavsdk::rpc::telemetry::Heading* mutable_heading_deg(); - void set_allocated_heading_deg(::mavsdk::rpc::telemetry::Heading* value); - void unsafe_arena_set_allocated_heading_deg(::mavsdk::rpc::telemetry::Heading* value); - ::mavsdk::rpc::telemetry::Heading* unsafe_arena_release_heading_deg(); + // .mavsdk.rpc.telemetry.Position home = 1; + bool has_home() const; + void clear_home() ; + const ::mavsdk::rpc::telemetry::Position& home() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Position* release_home(); + ::mavsdk::rpc::telemetry::Position* mutable_home(); + void set_allocated_home(::mavsdk::rpc::telemetry::Position* value); + void unsafe_arena_set_allocated_home(::mavsdk::rpc::telemetry::Position* value); + ::mavsdk::rpc::telemetry::Position* unsafe_arena_release_home(); private: - const ::mavsdk::rpc::telemetry::Heading& _internal_heading_deg() const; - ::mavsdk::rpc::telemetry::Heading* _internal_mutable_heading_deg(); + const ::mavsdk::rpc::telemetry::Position& _internal_home() const; + ::mavsdk::rpc::telemetry::Position* _internal_mutable_home(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HeadingResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HomeResponse) private: class _Internal; @@ -24253,33 +22883,33 @@ class HeadingResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::Heading* heading_deg_; + ::mavsdk::rpc::telemetry::Position* home_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GroundTruthResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GroundTruthResponse) */ { +class HealthResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HealthResponse) */ { public: - inline GroundTruthResponse() : GroundTruthResponse(nullptr) {} - ~GroundTruthResponse() override; + inline HealthResponse() : HealthResponse(nullptr) {} + ~HealthResponse() override; template - explicit PROTOBUF_CONSTEXPR GroundTruthResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR HealthResponse(::google::protobuf::internal::ConstantInitialized); - inline GroundTruthResponse(const GroundTruthResponse& from) - : GroundTruthResponse(nullptr, from) {} - GroundTruthResponse(GroundTruthResponse&& from) noexcept - : GroundTruthResponse() { + inline HealthResponse(const HealthResponse& from) + : HealthResponse(nullptr, from) {} + HealthResponse(HealthResponse&& from) noexcept + : HealthResponse() { *this = ::std::move(from); } - inline GroundTruthResponse& operator=(const GroundTruthResponse& from) { + inline HealthResponse& operator=(const HealthResponse& from) { CopyFrom(from); return *this; } - inline GroundTruthResponse& operator=(GroundTruthResponse&& from) noexcept { + inline HealthResponse& operator=(HealthResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -24311,20 +22941,20 @@ class GroundTruthResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GroundTruthResponse& default_instance() { + static const HealthResponse& default_instance() { return *internal_default_instance(); } - static inline const GroundTruthResponse* internal_default_instance() { - return reinterpret_cast( - &_GroundTruthResponse_default_instance_); + static inline const HealthResponse* internal_default_instance() { + return reinterpret_cast( + &_HealthResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 47; + 29; - friend void swap(GroundTruthResponse& a, GroundTruthResponse& b) { + friend void swap(HealthResponse& a, HealthResponse& b) { a.Swap(&b); } - inline void Swap(GroundTruthResponse* other) { + inline void Swap(HealthResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -24337,7 +22967,7 @@ class GroundTruthResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GroundTruthResponse* other) { + void UnsafeArenaSwap(HealthResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -24345,14 +22975,14 @@ class GroundTruthResponse final : // implements Message ---------------------------------------------- - GroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + HealthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GroundTruthResponse& from); + void CopyFrom(const HealthResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GroundTruthResponse& from) { - GroundTruthResponse::MergeImpl(*this, from); + void MergeFrom( const HealthResponse& from) { + HealthResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -24370,16 +23000,16 @@ class GroundTruthResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GroundTruthResponse* other); + void InternalSwap(HealthResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GroundTruthResponse"; + return "mavsdk.rpc.telemetry.HealthResponse"; } protected: - explicit GroundTruthResponse(::google::protobuf::Arena* arena); - GroundTruthResponse(::google::protobuf::Arena* arena, const GroundTruthResponse& from); + explicit HealthResponse(::google::protobuf::Arena* arena); + HealthResponse(::google::protobuf::Arena* arena, const HealthResponse& from); public: static const ClassData _class_data_; @@ -24392,24 +23022,24 @@ class GroundTruthResponse final : // accessors ------------------------------------------------------- enum : int { - kGroundTruthFieldNumber = 1, + kHealthFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; - bool has_ground_truth() const; - void clear_ground_truth() ; - const ::mavsdk::rpc::telemetry::GroundTruth& ground_truth() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GroundTruth* release_ground_truth(); - ::mavsdk::rpc::telemetry::GroundTruth* mutable_ground_truth(); - void set_allocated_ground_truth(::mavsdk::rpc::telemetry::GroundTruth* value); - void unsafe_arena_set_allocated_ground_truth(::mavsdk::rpc::telemetry::GroundTruth* value); - ::mavsdk::rpc::telemetry::GroundTruth* unsafe_arena_release_ground_truth(); + // .mavsdk.rpc.telemetry.Health health = 1; + bool has_health() const; + void clear_health() ; + const ::mavsdk::rpc::telemetry::Health& health() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Health* release_health(); + ::mavsdk::rpc::telemetry::Health* mutable_health(); + void set_allocated_health(::mavsdk::rpc::telemetry::Health* value); + void unsafe_arena_set_allocated_health(::mavsdk::rpc::telemetry::Health* value); + ::mavsdk::rpc::telemetry::Health* unsafe_arena_release_health(); private: - const ::mavsdk::rpc::telemetry::GroundTruth& _internal_ground_truth() const; - ::mavsdk::rpc::telemetry::GroundTruth* _internal_mutable_ground_truth(); + const ::mavsdk::rpc::telemetry::Health& _internal_health() const; + ::mavsdk::rpc::telemetry::Health* _internal_mutable_health(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GroundTruthResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HealthResponse) private: class _Internal; @@ -24434,33 +23064,33 @@ class GroundTruthResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::GroundTruth* ground_truth_; + ::mavsdk::rpc::telemetry::Health* health_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GpsInfoResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfoResponse) */ { +class HeadingResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.HeadingResponse) */ { public: - inline GpsInfoResponse() : GpsInfoResponse(nullptr) {} - ~GpsInfoResponse() override; + inline HeadingResponse() : HeadingResponse(nullptr) {} + ~HeadingResponse() override; template - explicit PROTOBUF_CONSTEXPR GpsInfoResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR HeadingResponse(::google::protobuf::internal::ConstantInitialized); - inline GpsInfoResponse(const GpsInfoResponse& from) - : GpsInfoResponse(nullptr, from) {} - GpsInfoResponse(GpsInfoResponse&& from) noexcept - : GpsInfoResponse() { + inline HeadingResponse(const HeadingResponse& from) + : HeadingResponse(nullptr, from) {} + HeadingResponse(HeadingResponse&& from) noexcept + : HeadingResponse() { *this = ::std::move(from); } - inline GpsInfoResponse& operator=(const GpsInfoResponse& from) { + inline HeadingResponse& operator=(const HeadingResponse& from) { CopyFrom(from); return *this; } - inline GpsInfoResponse& operator=(GpsInfoResponse&& from) noexcept { + inline HeadingResponse& operator=(HeadingResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -24492,20 +23122,20 @@ class GpsInfoResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GpsInfoResponse& default_instance() { + static const HeadingResponse& default_instance() { return *internal_default_instance(); } - static inline const GpsInfoResponse* internal_default_instance() { - return reinterpret_cast( - &_GpsInfoResponse_default_instance_); + static inline const HeadingResponse* internal_default_instance() { + return reinterpret_cast( + &_HeadingResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 25; + 61; - friend void swap(GpsInfoResponse& a, GpsInfoResponse& b) { + friend void swap(HeadingResponse& a, HeadingResponse& b) { a.Swap(&b); } - inline void Swap(GpsInfoResponse* other) { + inline void Swap(HeadingResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -24518,7 +23148,7 @@ class GpsInfoResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GpsInfoResponse* other) { + void UnsafeArenaSwap(HeadingResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -24526,14 +23156,14 @@ class GpsInfoResponse final : // implements Message ---------------------------------------------- - GpsInfoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + HeadingResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GpsInfoResponse& from); + void CopyFrom(const HeadingResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GpsInfoResponse& from) { - GpsInfoResponse::MergeImpl(*this, from); + void MergeFrom( const HeadingResponse& from) { + HeadingResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -24551,16 +23181,16 @@ class GpsInfoResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GpsInfoResponse* other); + void InternalSwap(HeadingResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GpsInfoResponse"; + return "mavsdk.rpc.telemetry.HeadingResponse"; } protected: - explicit GpsInfoResponse(::google::protobuf::Arena* arena); - GpsInfoResponse(::google::protobuf::Arena* arena, const GpsInfoResponse& from); + explicit HeadingResponse(::google::protobuf::Arena* arena); + HeadingResponse(::google::protobuf::Arena* arena, const HeadingResponse& from); public: static const ClassData _class_data_; @@ -24573,24 +23203,24 @@ class GpsInfoResponse final : // accessors ------------------------------------------------------- enum : int { - kGpsInfoFieldNumber = 1, + kHeadingDegFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; - bool has_gps_info() const; - void clear_gps_info() ; - const ::mavsdk::rpc::telemetry::GpsInfo& gps_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GpsInfo* release_gps_info(); - ::mavsdk::rpc::telemetry::GpsInfo* mutable_gps_info(); - void set_allocated_gps_info(::mavsdk::rpc::telemetry::GpsInfo* value); - void unsafe_arena_set_allocated_gps_info(::mavsdk::rpc::telemetry::GpsInfo* value); - ::mavsdk::rpc::telemetry::GpsInfo* unsafe_arena_release_gps_info(); + // .mavsdk.rpc.telemetry.Heading heading_deg = 1; + bool has_heading_deg() const; + void clear_heading_deg() ; + const ::mavsdk::rpc::telemetry::Heading& heading_deg() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Heading* release_heading_deg(); + ::mavsdk::rpc::telemetry::Heading* mutable_heading_deg(); + void set_allocated_heading_deg(::mavsdk::rpc::telemetry::Heading* value); + void unsafe_arena_set_allocated_heading_deg(::mavsdk::rpc::telemetry::Heading* value); + ::mavsdk::rpc::telemetry::Heading* unsafe_arena_release_heading_deg(); private: - const ::mavsdk::rpc::telemetry::GpsInfo& _internal_gps_info() const; - ::mavsdk::rpc::telemetry::GpsInfo* _internal_mutable_gps_info(); + const ::mavsdk::rpc::telemetry::Heading& _internal_heading_deg() const; + ::mavsdk::rpc::telemetry::Heading* _internal_mutable_heading_deg(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.HeadingResponse) private: class _Internal; @@ -24615,33 +23245,33 @@ class GpsInfoResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::GpsInfo* gps_info_; + ::mavsdk::rpc::telemetry::Heading* heading_deg_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class GetGpsGlobalOriginResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) */ { +class GroundTruthResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GroundTruthResponse) */ { public: - inline GetGpsGlobalOriginResponse() : GetGpsGlobalOriginResponse(nullptr) {} - ~GetGpsGlobalOriginResponse() override; + inline GroundTruthResponse() : GroundTruthResponse(nullptr) {} + ~GroundTruthResponse() override; template - explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GroundTruthResponse(::google::protobuf::internal::ConstantInitialized); - inline GetGpsGlobalOriginResponse(const GetGpsGlobalOriginResponse& from) - : GetGpsGlobalOriginResponse(nullptr, from) {} - GetGpsGlobalOriginResponse(GetGpsGlobalOriginResponse&& from) noexcept - : GetGpsGlobalOriginResponse() { + inline GroundTruthResponse(const GroundTruthResponse& from) + : GroundTruthResponse(nullptr, from) {} + GroundTruthResponse(GroundTruthResponse&& from) noexcept + : GroundTruthResponse() { *this = ::std::move(from); } - inline GetGpsGlobalOriginResponse& operator=(const GetGpsGlobalOriginResponse& from) { + inline GroundTruthResponse& operator=(const GroundTruthResponse& from) { CopyFrom(from); return *this; } - inline GetGpsGlobalOriginResponse& operator=(GetGpsGlobalOriginResponse&& from) noexcept { + inline GroundTruthResponse& operator=(GroundTruthResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -24673,20 +23303,20 @@ class GetGpsGlobalOriginResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GetGpsGlobalOriginResponse& default_instance() { + static const GroundTruthResponse& default_instance() { return *internal_default_instance(); } - static inline const GetGpsGlobalOriginResponse* internal_default_instance() { - return reinterpret_cast( - &_GetGpsGlobalOriginResponse_default_instance_); + static inline const GroundTruthResponse* internal_default_instance() { + return reinterpret_cast( + &_GroundTruthResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 120; + 43; - friend void swap(GetGpsGlobalOriginResponse& a, GetGpsGlobalOriginResponse& b) { + friend void swap(GroundTruthResponse& a, GroundTruthResponse& b) { a.Swap(&b); } - inline void Swap(GetGpsGlobalOriginResponse* other) { + inline void Swap(GroundTruthResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -24699,7 +23329,7 @@ class GetGpsGlobalOriginResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GetGpsGlobalOriginResponse* other) { + void UnsafeArenaSwap(GroundTruthResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -24707,14 +23337,14 @@ class GetGpsGlobalOriginResponse final : // implements Message ---------------------------------------------- - GetGpsGlobalOriginResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const GetGpsGlobalOriginResponse& from); + void CopyFrom(const GroundTruthResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const GetGpsGlobalOriginResponse& from) { - GetGpsGlobalOriginResponse::MergeImpl(*this, from); + void MergeFrom( const GroundTruthResponse& from) { + GroundTruthResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -24732,16 +23362,16 @@ class GetGpsGlobalOriginResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(GetGpsGlobalOriginResponse* other); + void InternalSwap(GroundTruthResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse"; + return "mavsdk.rpc.telemetry.GroundTruthResponse"; } protected: - explicit GetGpsGlobalOriginResponse(::google::protobuf::Arena* arena); - GetGpsGlobalOriginResponse(::google::protobuf::Arena* arena, const GetGpsGlobalOriginResponse& from); + explicit GroundTruthResponse(::google::protobuf::Arena* arena); + GroundTruthResponse(::google::protobuf::Arena* arena, const GroundTruthResponse& from); public: static const ClassData _class_data_; @@ -24754,46 +23384,30 @@ class GetGpsGlobalOriginResponse final : // accessors ------------------------------------------------------- enum : int { - kTelemetryResultFieldNumber = 1, - kGpsGlobalOriginFieldNumber = 2, + kGroundTruthFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; - bool has_telemetry_result() const; - void clear_telemetry_result() ; - const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); - ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); - void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); - ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); - - private: - const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; - ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); - - public: - // .mavsdk.rpc.telemetry.GpsGlobalOrigin gps_global_origin = 2; - bool has_gps_global_origin() const; - void clear_gps_global_origin() ; - const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& gps_global_origin() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GpsGlobalOrigin* release_gps_global_origin(); - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* mutable_gps_global_origin(); - void set_allocated_gps_global_origin(::mavsdk::rpc::telemetry::GpsGlobalOrigin* value); - void unsafe_arena_set_allocated_gps_global_origin(::mavsdk::rpc::telemetry::GpsGlobalOrigin* value); - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* unsafe_arena_release_gps_global_origin(); + // .mavsdk.rpc.telemetry.GroundTruth ground_truth = 1; + bool has_ground_truth() const; + void clear_ground_truth() ; + const ::mavsdk::rpc::telemetry::GroundTruth& ground_truth() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GroundTruth* release_ground_truth(); + ::mavsdk::rpc::telemetry::GroundTruth* mutable_ground_truth(); + void set_allocated_ground_truth(::mavsdk::rpc::telemetry::GroundTruth* value); + void unsafe_arena_set_allocated_ground_truth(::mavsdk::rpc::telemetry::GroundTruth* value); + ::mavsdk::rpc::telemetry::GroundTruth* unsafe_arena_release_ground_truth(); private: - const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& _internal_gps_global_origin() const; - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* _internal_mutable_gps_global_origin(); + const ::mavsdk::rpc::telemetry::GroundTruth& _internal_ground_truth() const; + ::mavsdk::rpc::telemetry::GroundTruth* _internal_mutable_ground_truth(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GroundTruthResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 2, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -24812,34 +23426,33 @@ class GetGpsGlobalOriginResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin_; + ::mavsdk::rpc::telemetry::GroundTruth* ground_truth_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class FixedwingMetricsResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FixedwingMetricsResponse) */ { +class GpsInfoResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfoResponse) */ { public: - inline FixedwingMetricsResponse() : FixedwingMetricsResponse(nullptr) {} - ~FixedwingMetricsResponse() override; + inline GpsInfoResponse() : GpsInfoResponse(nullptr) {} + ~GpsInfoResponse() override; template - explicit PROTOBUF_CONSTEXPR FixedwingMetricsResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GpsInfoResponse(::google::protobuf::internal::ConstantInitialized); - inline FixedwingMetricsResponse(const FixedwingMetricsResponse& from) - : FixedwingMetricsResponse(nullptr, from) {} - FixedwingMetricsResponse(FixedwingMetricsResponse&& from) noexcept - : FixedwingMetricsResponse() { + inline GpsInfoResponse(const GpsInfoResponse& from) + : GpsInfoResponse(nullptr, from) {} + GpsInfoResponse(GpsInfoResponse&& from) noexcept + : GpsInfoResponse() { *this = ::std::move(from); } - inline FixedwingMetricsResponse& operator=(const FixedwingMetricsResponse& from) { + inline GpsInfoResponse& operator=(const GpsInfoResponse& from) { CopyFrom(from); return *this; } - inline FixedwingMetricsResponse& operator=(FixedwingMetricsResponse&& from) noexcept { + inline GpsInfoResponse& operator=(GpsInfoResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -24871,20 +23484,20 @@ class FixedwingMetricsResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const FixedwingMetricsResponse& default_instance() { + static const GpsInfoResponse& default_instance() { return *internal_default_instance(); } - static inline const FixedwingMetricsResponse* internal_default_instance() { - return reinterpret_cast( - &_FixedwingMetricsResponse_default_instance_); + static inline const GpsInfoResponse* internal_default_instance() { + return reinterpret_cast( + &_GpsInfoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 49; + 21; - friend void swap(FixedwingMetricsResponse& a, FixedwingMetricsResponse& b) { + friend void swap(GpsInfoResponse& a, GpsInfoResponse& b) { a.Swap(&b); } - inline void Swap(FixedwingMetricsResponse* other) { + inline void Swap(GpsInfoResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -24897,7 +23510,7 @@ class FixedwingMetricsResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(FixedwingMetricsResponse* other) { + void UnsafeArenaSwap(GpsInfoResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -24905,14 +23518,14 @@ class FixedwingMetricsResponse final : // implements Message ---------------------------------------------- - FixedwingMetricsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GpsInfoResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const FixedwingMetricsResponse& from); + void CopyFrom(const GpsInfoResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const FixedwingMetricsResponse& from) { - FixedwingMetricsResponse::MergeImpl(*this, from); + void MergeFrom( const GpsInfoResponse& from) { + GpsInfoResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -24930,16 +23543,16 @@ class FixedwingMetricsResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(FixedwingMetricsResponse* other); + void InternalSwap(GpsInfoResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.FixedwingMetricsResponse"; + return "mavsdk.rpc.telemetry.GpsInfoResponse"; } protected: - explicit FixedwingMetricsResponse(::google::protobuf::Arena* arena); - FixedwingMetricsResponse(::google::protobuf::Arena* arena, const FixedwingMetricsResponse& from); + explicit GpsInfoResponse(::google::protobuf::Arena* arena); + GpsInfoResponse(::google::protobuf::Arena* arena, const GpsInfoResponse& from); public: static const ClassData _class_data_; @@ -24952,24 +23565,24 @@ class FixedwingMetricsResponse final : // accessors ------------------------------------------------------- enum : int { - kFixedwingMetricsFieldNumber = 1, + kGpsInfoFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; - bool has_fixedwing_metrics() const; - void clear_fixedwing_metrics() ; - const ::mavsdk::rpc::telemetry::FixedwingMetrics& fixedwing_metrics() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::FixedwingMetrics* release_fixedwing_metrics(); - ::mavsdk::rpc::telemetry::FixedwingMetrics* mutable_fixedwing_metrics(); - void set_allocated_fixedwing_metrics(::mavsdk::rpc::telemetry::FixedwingMetrics* value); - void unsafe_arena_set_allocated_fixedwing_metrics(::mavsdk::rpc::telemetry::FixedwingMetrics* value); - ::mavsdk::rpc::telemetry::FixedwingMetrics* unsafe_arena_release_fixedwing_metrics(); + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + bool has_gps_info() const; + void clear_gps_info() ; + const ::mavsdk::rpc::telemetry::GpsInfo& gps_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GpsInfo* release_gps_info(); + ::mavsdk::rpc::telemetry::GpsInfo* mutable_gps_info(); + void set_allocated_gps_info(::mavsdk::rpc::telemetry::GpsInfo* value); + void unsafe_arena_set_allocated_gps_info(::mavsdk::rpc::telemetry::GpsInfo* value); + ::mavsdk::rpc::telemetry::GpsInfo* unsafe_arena_release_gps_info(); private: - const ::mavsdk::rpc::telemetry::FixedwingMetrics& _internal_fixedwing_metrics() const; - ::mavsdk::rpc::telemetry::FixedwingMetrics* _internal_mutable_fixedwing_metrics(); + const ::mavsdk::rpc::telemetry::GpsInfo& _internal_gps_info() const; + ::mavsdk::rpc::telemetry::GpsInfo* _internal_mutable_gps_info(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FixedwingMetricsResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfoResponse) private: class _Internal; @@ -24994,33 +23607,33 @@ class FixedwingMetricsResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::FixedwingMetrics* fixedwing_metrics_; + ::mavsdk::rpc::telemetry::GpsInfo* gps_info_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class DistanceSensor final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.DistanceSensor) */ { +class GetGpsGlobalOriginResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) */ { public: - inline DistanceSensor() : DistanceSensor(nullptr) {} - ~DistanceSensor() override; + inline GetGpsGlobalOriginResponse() : GetGpsGlobalOriginResponse(nullptr) {} + ~GetGpsGlobalOriginResponse() override; template - explicit PROTOBUF_CONSTEXPR DistanceSensor(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginResponse(::google::protobuf::internal::ConstantInitialized); - inline DistanceSensor(const DistanceSensor& from) - : DistanceSensor(nullptr, from) {} - DistanceSensor(DistanceSensor&& from) noexcept - : DistanceSensor() { + inline GetGpsGlobalOriginResponse(const GetGpsGlobalOriginResponse& from) + : GetGpsGlobalOriginResponse(nullptr, from) {} + GetGpsGlobalOriginResponse(GetGpsGlobalOriginResponse&& from) noexcept + : GetGpsGlobalOriginResponse() { *this = ::std::move(from); } - inline DistanceSensor& operator=(const DistanceSensor& from) { + inline GetGpsGlobalOriginResponse& operator=(const GetGpsGlobalOriginResponse& from) { CopyFrom(from); return *this; } - inline DistanceSensor& operator=(DistanceSensor&& from) noexcept { + inline GetGpsGlobalOriginResponse& operator=(GetGpsGlobalOriginResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -25052,20 +23665,20 @@ class DistanceSensor final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const DistanceSensor& default_instance() { + static const GetGpsGlobalOriginResponse& default_instance() { return *internal_default_instance(); } - static inline const DistanceSensor* internal_default_instance() { - return reinterpret_cast( - &_DistanceSensor_default_instance_); + static inline const GetGpsGlobalOriginResponse* internal_default_instance() { + return reinterpret_cast( + &_GetGpsGlobalOriginResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 140; + 112; - friend void swap(DistanceSensor& a, DistanceSensor& b) { + friend void swap(GetGpsGlobalOriginResponse& a, GetGpsGlobalOriginResponse& b) { a.Swap(&b); } - inline void Swap(DistanceSensor* other) { + inline void Swap(GetGpsGlobalOriginResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -25078,7 +23691,7 @@ class DistanceSensor final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(DistanceSensor* other) { + void UnsafeArenaSwap(GetGpsGlobalOriginResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -25086,14 +23699,14 @@ class DistanceSensor final : // implements Message ---------------------------------------------- - DistanceSensor* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GetGpsGlobalOriginResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const DistanceSensor& from); + void CopyFrom(const GetGpsGlobalOriginResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const DistanceSensor& from) { - DistanceSensor::MergeImpl(*this, from); + void MergeFrom( const GetGpsGlobalOriginResponse& from) { + GetGpsGlobalOriginResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -25111,16 +23724,16 @@ class DistanceSensor final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(DistanceSensor* other); + void InternalSwap(GetGpsGlobalOriginResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.DistanceSensor"; + return "mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse"; } protected: - explicit DistanceSensor(::google::protobuf::Arena* arena); - DistanceSensor(::google::protobuf::Arena* arena, const DistanceSensor& from); + explicit GetGpsGlobalOriginResponse(::google::protobuf::Arena* arena); + GetGpsGlobalOriginResponse(::google::protobuf::Arena* arena, const GetGpsGlobalOriginResponse& from); public: static const ClassData _class_data_; @@ -25133,63 +23746,46 @@ class DistanceSensor final : // accessors ------------------------------------------------------- enum : int { - kOrientationFieldNumber = 4, - kMinimumDistanceMFieldNumber = 1, - kMaximumDistanceMFieldNumber = 2, - kCurrentDistanceMFieldNumber = 3, + kTelemetryResultFieldNumber = 1, + kGpsGlobalOriginFieldNumber = 2, }; - // .mavsdk.rpc.telemetry.EulerAngle orientation = 4; - bool has_orientation() const; - void clear_orientation() ; - const ::mavsdk::rpc::telemetry::EulerAngle& orientation() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::EulerAngle* release_orientation(); - ::mavsdk::rpc::telemetry::EulerAngle* mutable_orientation(); - void set_allocated_orientation(::mavsdk::rpc::telemetry::EulerAngle* value); - void unsafe_arena_set_allocated_orientation(::mavsdk::rpc::telemetry::EulerAngle* value); - ::mavsdk::rpc::telemetry::EulerAngle* unsafe_arena_release_orientation(); - - private: - const ::mavsdk::rpc::telemetry::EulerAngle& _internal_orientation() const; - ::mavsdk::rpc::telemetry::EulerAngle* _internal_mutable_orientation(); - - public: - // float minimum_distance_m = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_minimum_distance_m() ; - float minimum_distance_m() const; - void set_minimum_distance_m(float value); - - private: - float _internal_minimum_distance_m() const; - void _internal_set_minimum_distance_m(float value); - - public: - // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_maximum_distance_m() ; - float maximum_distance_m() const; - void set_maximum_distance_m(float value); + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + void clear_telemetry_result() ; + const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::TelemetryResult* release_telemetry_result(); + ::mavsdk::rpc::telemetry::TelemetryResult* mutable_telemetry_result(); + void set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + void unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); private: - float _internal_maximum_distance_m() const; - void _internal_set_maximum_distance_m(float value); + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); public: - // float current_distance_m = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_current_distance_m() ; - float current_distance_m() const; - void set_current_distance_m(float value); + // .mavsdk.rpc.telemetry.GpsGlobalOrigin gps_global_origin = 2; + bool has_gps_global_origin() const; + void clear_gps_global_origin() ; + const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& gps_global_origin() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::GpsGlobalOrigin* release_gps_global_origin(); + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* mutable_gps_global_origin(); + void set_allocated_gps_global_origin(::mavsdk::rpc::telemetry::GpsGlobalOrigin* value); + void unsafe_arena_set_allocated_gps_global_origin(::mavsdk::rpc::telemetry::GpsGlobalOrigin* value); + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* unsafe_arena_release_gps_global_origin(); private: - float _internal_current_distance_m() const; - void _internal_set_current_distance_m(float value); + const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& _internal_gps_global_origin() const; + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* _internal_mutable_gps_global_origin(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.DistanceSensor) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 4, 1, + 1, 2, 2, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -25208,36 +23804,34 @@ class DistanceSensor final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::EulerAngle* orientation_; - float minimum_distance_m_; - float maximum_distance_m_; - float current_distance_m_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class CameraAttitudeQuaternionResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) */ { +class FixedwingMetricsResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.FixedwingMetricsResponse) */ { public: - inline CameraAttitudeQuaternionResponse() : CameraAttitudeQuaternionResponse(nullptr) {} - ~CameraAttitudeQuaternionResponse() override; + inline FixedwingMetricsResponse() : FixedwingMetricsResponse(nullptr) {} + ~FixedwingMetricsResponse() override; template - explicit PROTOBUF_CONSTEXPR CameraAttitudeQuaternionResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR FixedwingMetricsResponse(::google::protobuf::internal::ConstantInitialized); - inline CameraAttitudeQuaternionResponse(const CameraAttitudeQuaternionResponse& from) - : CameraAttitudeQuaternionResponse(nullptr, from) {} - CameraAttitudeQuaternionResponse(CameraAttitudeQuaternionResponse&& from) noexcept - : CameraAttitudeQuaternionResponse() { + inline FixedwingMetricsResponse(const FixedwingMetricsResponse& from) + : FixedwingMetricsResponse(nullptr, from) {} + FixedwingMetricsResponse(FixedwingMetricsResponse&& from) noexcept + : FixedwingMetricsResponse() { *this = ::std::move(from); } - inline CameraAttitudeQuaternionResponse& operator=(const CameraAttitudeQuaternionResponse& from) { + inline FixedwingMetricsResponse& operator=(const FixedwingMetricsResponse& from) { CopyFrom(from); return *this; } - inline CameraAttitudeQuaternionResponse& operator=(CameraAttitudeQuaternionResponse&& from) noexcept { + inline FixedwingMetricsResponse& operator=(FixedwingMetricsResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -25269,20 +23863,20 @@ class CameraAttitudeQuaternionResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CameraAttitudeQuaternionResponse& default_instance() { + static const FixedwingMetricsResponse& default_instance() { return *internal_default_instance(); } - static inline const CameraAttitudeQuaternionResponse* internal_default_instance() { - return reinterpret_cast( - &_CameraAttitudeQuaternionResponse_default_instance_); + static inline const FixedwingMetricsResponse* internal_default_instance() { + return reinterpret_cast( + &_FixedwingMetricsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 45; - friend void swap(CameraAttitudeQuaternionResponse& a, CameraAttitudeQuaternionResponse& b) { + friend void swap(FixedwingMetricsResponse& a, FixedwingMetricsResponse& b) { a.Swap(&b); } - inline void Swap(CameraAttitudeQuaternionResponse* other) { + inline void Swap(FixedwingMetricsResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -25295,7 +23889,7 @@ class CameraAttitudeQuaternionResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CameraAttitudeQuaternionResponse* other) { + void UnsafeArenaSwap(FixedwingMetricsResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -25303,14 +23897,14 @@ class CameraAttitudeQuaternionResponse final : // implements Message ---------------------------------------------- - CameraAttitudeQuaternionResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + FixedwingMetricsResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CameraAttitudeQuaternionResponse& from); + void CopyFrom(const FixedwingMetricsResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CameraAttitudeQuaternionResponse& from) { - CameraAttitudeQuaternionResponse::MergeImpl(*this, from); + void MergeFrom( const FixedwingMetricsResponse& from) { + FixedwingMetricsResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -25328,16 +23922,16 @@ class CameraAttitudeQuaternionResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CameraAttitudeQuaternionResponse* other); + void InternalSwap(FixedwingMetricsResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse"; + return "mavsdk.rpc.telemetry.FixedwingMetricsResponse"; } protected: - explicit CameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena); - CameraAttitudeQuaternionResponse(::google::protobuf::Arena* arena, const CameraAttitudeQuaternionResponse& from); + explicit FixedwingMetricsResponse(::google::protobuf::Arena* arena); + FixedwingMetricsResponse(::google::protobuf::Arena* arena, const FixedwingMetricsResponse& from); public: static const ClassData _class_data_; @@ -25350,24 +23944,24 @@ class CameraAttitudeQuaternionResponse final : // accessors ------------------------------------------------------- enum : int { - kAttitudeQuaternionFieldNumber = 1, + kFixedwingMetricsFieldNumber = 1, }; - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; - bool has_attitude_quaternion() const; - void clear_attitude_quaternion() ; - const ::mavsdk::rpc::telemetry::Quaternion& attitude_quaternion() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Quaternion* release_attitude_quaternion(); - ::mavsdk::rpc::telemetry::Quaternion* mutable_attitude_quaternion(); - void set_allocated_attitude_quaternion(::mavsdk::rpc::telemetry::Quaternion* value); - void unsafe_arena_set_allocated_attitude_quaternion(::mavsdk::rpc::telemetry::Quaternion* value); - ::mavsdk::rpc::telemetry::Quaternion* unsafe_arena_release_attitude_quaternion(); + // .mavsdk.rpc.telemetry.FixedwingMetrics fixedwing_metrics = 1; + bool has_fixedwing_metrics() const; + void clear_fixedwing_metrics() ; + const ::mavsdk::rpc::telemetry::FixedwingMetrics& fixedwing_metrics() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::FixedwingMetrics* release_fixedwing_metrics(); + ::mavsdk::rpc::telemetry::FixedwingMetrics* mutable_fixedwing_metrics(); + void set_allocated_fixedwing_metrics(::mavsdk::rpc::telemetry::FixedwingMetrics* value); + void unsafe_arena_set_allocated_fixedwing_metrics(::mavsdk::rpc::telemetry::FixedwingMetrics* value); + ::mavsdk::rpc::telemetry::FixedwingMetrics* unsafe_arena_release_fixedwing_metrics(); private: - const ::mavsdk::rpc::telemetry::Quaternion& _internal_attitude_quaternion() const; - ::mavsdk::rpc::telemetry::Quaternion* _internal_mutable_attitude_quaternion(); + const ::mavsdk::rpc::telemetry::FixedwingMetrics& _internal_fixedwing_metrics() const; + ::mavsdk::rpc::telemetry::FixedwingMetrics* _internal_mutable_fixedwing_metrics(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FixedwingMetricsResponse) private: class _Internal; @@ -25392,33 +23986,33 @@ class CameraAttitudeQuaternionResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::Quaternion* attitude_quaternion_; + ::mavsdk::rpc::telemetry::FixedwingMetrics* fixedwing_metrics_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; };// ------------------------------------------------------------------- -class CameraAttitudeEulerResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) */ { +class DistanceSensor final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.DistanceSensor) */ { public: - inline CameraAttitudeEulerResponse() : CameraAttitudeEulerResponse(nullptr) {} - ~CameraAttitudeEulerResponse() override; + inline DistanceSensor() : DistanceSensor(nullptr) {} + ~DistanceSensor() override; template - explicit PROTOBUF_CONSTEXPR CameraAttitudeEulerResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR DistanceSensor(::google::protobuf::internal::ConstantInitialized); - inline CameraAttitudeEulerResponse(const CameraAttitudeEulerResponse& from) - : CameraAttitudeEulerResponse(nullptr, from) {} - CameraAttitudeEulerResponse(CameraAttitudeEulerResponse&& from) noexcept - : CameraAttitudeEulerResponse() { + inline DistanceSensor(const DistanceSensor& from) + : DistanceSensor(nullptr, from) {} + DistanceSensor(DistanceSensor&& from) noexcept + : DistanceSensor() { *this = ::std::move(from); } - inline CameraAttitudeEulerResponse& operator=(const CameraAttitudeEulerResponse& from) { + inline DistanceSensor& operator=(const DistanceSensor& from) { CopyFrom(from); return *this; } - inline CameraAttitudeEulerResponse& operator=(CameraAttitudeEulerResponse&& from) noexcept { + inline DistanceSensor& operator=(DistanceSensor&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -25450,20 +24044,20 @@ class CameraAttitudeEulerResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const CameraAttitudeEulerResponse& default_instance() { + static const DistanceSensor& default_instance() { return *internal_default_instance(); } - static inline const CameraAttitudeEulerResponse* internal_default_instance() { - return reinterpret_cast( - &_CameraAttitudeEulerResponse_default_instance_); + static inline const DistanceSensor* internal_default_instance() { + return reinterpret_cast( + &_DistanceSensor_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 132; - friend void swap(CameraAttitudeEulerResponse& a, CameraAttitudeEulerResponse& b) { + friend void swap(DistanceSensor& a, DistanceSensor& b) { a.Swap(&b); } - inline void Swap(CameraAttitudeEulerResponse* other) { + inline void Swap(DistanceSensor* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -25476,7 +24070,7 @@ class CameraAttitudeEulerResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(CameraAttitudeEulerResponse* other) { + void UnsafeArenaSwap(DistanceSensor* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -25484,14 +24078,14 @@ class CameraAttitudeEulerResponse final : // implements Message ---------------------------------------------- - CameraAttitudeEulerResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + DistanceSensor* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const CameraAttitudeEulerResponse& from); + void CopyFrom(const DistanceSensor& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const CameraAttitudeEulerResponse& from) { - CameraAttitudeEulerResponse::MergeImpl(*this, from); + void MergeFrom( const DistanceSensor& from) { + DistanceSensor::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -25509,52 +24103,85 @@ class CameraAttitudeEulerResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(CameraAttitudeEulerResponse* other); + void InternalSwap(DistanceSensor* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.telemetry.CameraAttitudeEulerResponse"; + return "mavsdk.rpc.telemetry.DistanceSensor"; } protected: - explicit CameraAttitudeEulerResponse(::google::protobuf::Arena* arena); - CameraAttitudeEulerResponse(::google::protobuf::Arena* arena, const CameraAttitudeEulerResponse& from); + explicit DistanceSensor(::google::protobuf::Arena* arena); + DistanceSensor(::google::protobuf::Arena* arena, const DistanceSensor& from); public: static const ClassData _class_data_; const ::google::protobuf::Message::ClassData*GetClassData() const final; - ::google::protobuf::Metadata GetMetadata() const final; + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kOrientationFieldNumber = 4, + kMinimumDistanceMFieldNumber = 1, + kMaximumDistanceMFieldNumber = 2, + kCurrentDistanceMFieldNumber = 3, + }; + // .mavsdk.rpc.telemetry.EulerAngle orientation = 4; + bool has_orientation() const; + void clear_orientation() ; + const ::mavsdk::rpc::telemetry::EulerAngle& orientation() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::EulerAngle* release_orientation(); + ::mavsdk::rpc::telemetry::EulerAngle* mutable_orientation(); + void set_allocated_orientation(::mavsdk::rpc::telemetry::EulerAngle* value); + void unsafe_arena_set_allocated_orientation(::mavsdk::rpc::telemetry::EulerAngle* value); + ::mavsdk::rpc::telemetry::EulerAngle* unsafe_arena_release_orientation(); + + private: + const ::mavsdk::rpc::telemetry::EulerAngle& _internal_orientation() const; + ::mavsdk::rpc::telemetry::EulerAngle* _internal_mutable_orientation(); + + public: + // float minimum_distance_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_minimum_distance_m() ; + float minimum_distance_m() const; + void set_minimum_distance_m(float value); + + private: + float _internal_minimum_distance_m() const; + void _internal_set_minimum_distance_m(float value); - // nested types ---------------------------------------------------- + public: + // float maximum_distance_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_maximum_distance_m() ; + float maximum_distance_m() const; + void set_maximum_distance_m(float value); - // accessors ------------------------------------------------------- + private: + float _internal_maximum_distance_m() const; + void _internal_set_maximum_distance_m(float value); - enum : int { - kAttitudeEulerFieldNumber = 1, - }; - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; - bool has_attitude_euler() const; - void clear_attitude_euler() ; - const ::mavsdk::rpc::telemetry::EulerAngle& attitude_euler() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::EulerAngle* release_attitude_euler(); - ::mavsdk::rpc::telemetry::EulerAngle* mutable_attitude_euler(); - void set_allocated_attitude_euler(::mavsdk::rpc::telemetry::EulerAngle* value); - void unsafe_arena_set_allocated_attitude_euler(::mavsdk::rpc::telemetry::EulerAngle* value); - ::mavsdk::rpc::telemetry::EulerAngle* unsafe_arena_release_attitude_euler(); + public: + // float current_distance_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_current_distance_m() ; + float current_distance_m() const; + void set_current_distance_m(float value); private: - const ::mavsdk::rpc::telemetry::EulerAngle& _internal_attitude_euler() const; - ::mavsdk::rpc::telemetry::EulerAngle* _internal_mutable_attitude_euler(); + float _internal_current_distance_m() const; + void _internal_set_current_distance_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.DistanceSensor) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 4, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -25573,7 +24200,10 @@ class CameraAttitudeEulerResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry::EulerAngle* attitude_euler_; + ::mavsdk::rpc::telemetry::EulerAngle* orientation_; + float minimum_distance_m_; + float maximum_distance_m_; + float current_distance_m_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -25639,7 +24269,7 @@ class BatteryResponse final : &_BatteryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 29; + 25; friend void swap(BatteryResponse& a, BatteryResponse& b) { a.Swap(&b); @@ -26363,7 +24993,7 @@ class AltitudeResponse final : &_AltitudeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 67; + 63; friend void swap(AltitudeResponse& a, AltitudeResponse& b) { a.Swap(&b); @@ -26544,7 +25174,7 @@ class ActuatorOutputStatusResponse final : &_ActuatorOutputStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 41; + 37; friend void swap(ActuatorOutputStatusResponse& a, ActuatorOutputStatusResponse& b) { a.Swap(&b); @@ -26725,7 +25355,7 @@ class ActuatorControlTargetResponse final : &_ActuatorControlTargetResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 39; + 35; friend void swap(ActuatorControlTargetResponse& a, ActuatorControlTargetResponse& b) { a.Swap(&b); @@ -26906,7 +25536,7 @@ class ScaledImuResponse final : &_ScaledImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 53; + 49; friend void swap(ScaledImuResponse& a, ScaledImuResponse& b) { a.Swap(&b); @@ -27087,7 +25717,7 @@ class RawImuResponse final : &_RawImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 55; + 51; friend void swap(RawImuResponse& a, RawImuResponse& b) { a.Swap(&b); @@ -27268,7 +25898,7 @@ class PositionVelocityNedResponse final : &_PositionVelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 45; + 41; friend void swap(PositionVelocityNedResponse& a, PositionVelocityNedResponse& b) { a.Swap(&b); @@ -27449,7 +26079,7 @@ class OdometryResponse final : &_OdometryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 43; + 39; friend void swap(OdometryResponse& a, OdometryResponse& b) { a.Swap(&b); @@ -27630,7 +26260,7 @@ class ImuResponse final : &_ImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 51; + 47; friend void swap(ImuResponse& a, ImuResponse& b) { a.Swap(&b); @@ -27811,7 +26441,7 @@ class DistanceSensorResponse final : &_DistanceSensorResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 61; + 57; friend void swap(DistanceSensorResponse& a, DistanceSensorResponse& b) { a.Swap(&b); @@ -28499,247 +27129,39 @@ inline bool AttitudeAngularVelocityBodyResponse::has_attitude_angular_velocity_b PROTOBUF_ASSUME(!value || _impl_.attitude_angular_velocity_body_ != nullptr); return value; } -inline void AttitudeAngularVelocityBodyResponse::clear_attitude_angular_velocity_body() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.attitude_angular_velocity_body_ != nullptr) _impl_.attitude_angular_velocity_body_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::telemetry::AngularVelocityBody& AttitudeAngularVelocityBodyResponse::_internal_attitude_angular_velocity_body() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::telemetry::AngularVelocityBody* p = _impl_.attitude_angular_velocity_body_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_AngularVelocityBody_default_instance_); -} -inline const ::mavsdk::rpc::telemetry::AngularVelocityBody& AttitudeAngularVelocityBodyResponse::attitude_angular_velocity_body() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) - return _internal_attitude_angular_velocity_body(); -} -inline void AttitudeAngularVelocityBodyResponse::unsafe_arena_set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_angular_velocity_body_); - } - _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) -} -inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::release_attitude_angular_velocity_body() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::AngularVelocityBody* released = _impl_.attitude_angular_velocity_body_; - _impl_.attitude_angular_velocity_body_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; -} -inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::unsafe_arena_release_attitude_angular_velocity_body() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::AngularVelocityBody* temp = _impl_.attitude_angular_velocity_body_; - _impl_.attitude_angular_velocity_body_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::_internal_mutable_attitude_angular_velocity_body() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.attitude_angular_velocity_body_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityBody>(GetArena()); - _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(p); - } - return _impl_.attitude_angular_velocity_body_; -} -inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::mutable_attitude_angular_velocity_body() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::telemetry::AngularVelocityBody* _msg = _internal_mutable_attitude_angular_velocity_body(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) - return _msg; -} -inline void AttitudeAngularVelocityBodyResponse::set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(_impl_.attitude_angular_velocity_body_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) -} - -// ------------------------------------------------------------------- - -// SubscribeCameraAttitudeQuaternionRequest - -// ------------------------------------------------------------------- - -// CameraAttitudeQuaternionResponse - -// .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; -inline bool CameraAttitudeQuaternionResponse::has_attitude_quaternion() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.attitude_quaternion_ != nullptr); - return value; -} -inline void CameraAttitudeQuaternionResponse::clear_attitude_quaternion() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.attitude_quaternion_ != nullptr) _impl_.attitude_quaternion_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::telemetry::Quaternion& CameraAttitudeQuaternionResponse::_internal_attitude_quaternion() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::telemetry::Quaternion* p = _impl_.attitude_quaternion_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_Quaternion_default_instance_); -} -inline const ::mavsdk::rpc::telemetry::Quaternion& CameraAttitudeQuaternionResponse::attitude_quaternion() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse.attitude_quaternion) - return _internal_attitude_quaternion(); -} -inline void CameraAttitudeQuaternionResponse::unsafe_arena_set_allocated_attitude_quaternion(::mavsdk::rpc::telemetry::Quaternion* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_quaternion_); - } - _impl_.attitude_quaternion_ = reinterpret_cast<::mavsdk::rpc::telemetry::Quaternion*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse.attitude_quaternion) -} -inline ::mavsdk::rpc::telemetry::Quaternion* CameraAttitudeQuaternionResponse::release_attitude_quaternion() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::Quaternion* released = _impl_.attitude_quaternion_; - _impl_.attitude_quaternion_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; -} -inline ::mavsdk::rpc::telemetry::Quaternion* CameraAttitudeQuaternionResponse::unsafe_arena_release_attitude_quaternion() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse.attitude_quaternion) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::Quaternion* temp = _impl_.attitude_quaternion_; - _impl_.attitude_quaternion_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::telemetry::Quaternion* CameraAttitudeQuaternionResponse::_internal_mutable_attitude_quaternion() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.attitude_quaternion_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::Quaternion>(GetArena()); - _impl_.attitude_quaternion_ = reinterpret_cast<::mavsdk::rpc::telemetry::Quaternion*>(p); - } - return _impl_.attitude_quaternion_; -} -inline ::mavsdk::rpc::telemetry::Quaternion* CameraAttitudeQuaternionResponse::mutable_attitude_quaternion() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::telemetry::Quaternion* _msg = _internal_mutable_attitude_quaternion(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse.attitude_quaternion) - return _msg; -} -inline void CameraAttitudeQuaternionResponse::set_allocated_attitude_quaternion(::mavsdk::rpc::telemetry::Quaternion* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::telemetry::Quaternion*>(_impl_.attitude_quaternion_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::Quaternion*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.attitude_quaternion_ = reinterpret_cast<::mavsdk::rpc::telemetry::Quaternion*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse.attitude_quaternion) -} - -// ------------------------------------------------------------------- - -// SubscribeCameraAttitudeEulerRequest - -// ------------------------------------------------------------------- - -// CameraAttitudeEulerResponse - -// .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; -inline bool CameraAttitudeEulerResponse::has_attitude_euler() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.attitude_euler_ != nullptr); - return value; -} -inline void CameraAttitudeEulerResponse::clear_attitude_euler() { +inline void AttitudeAngularVelocityBodyResponse::clear_attitude_angular_velocity_body() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.attitude_euler_ != nullptr) _impl_.attitude_euler_->Clear(); + if (_impl_.attitude_angular_velocity_body_ != nullptr) _impl_.attitude_angular_velocity_body_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::telemetry::EulerAngle& CameraAttitudeEulerResponse::_internal_attitude_euler() const { +inline const ::mavsdk::rpc::telemetry::AngularVelocityBody& AttitudeAngularVelocityBodyResponse::_internal_attitude_angular_velocity_body() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::telemetry::EulerAngle* p = _impl_.attitude_euler_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_EulerAngle_default_instance_); + const ::mavsdk::rpc::telemetry::AngularVelocityBody* p = _impl_.attitude_angular_velocity_body_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_AngularVelocityBody_default_instance_); } -inline const ::mavsdk::rpc::telemetry::EulerAngle& CameraAttitudeEulerResponse::attitude_euler() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse.attitude_euler) - return _internal_attitude_euler(); +inline const ::mavsdk::rpc::telemetry::AngularVelocityBody& AttitudeAngularVelocityBodyResponse::attitude_angular_velocity_body() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) + return _internal_attitude_angular_velocity_body(); } -inline void CameraAttitudeEulerResponse::unsafe_arena_set_allocated_attitude_euler(::mavsdk::rpc::telemetry::EulerAngle* value) { +inline void AttitudeAngularVelocityBodyResponse::unsafe_arena_set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_euler_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_angular_velocity_body_); } - _impl_.attitude_euler_ = reinterpret_cast<::mavsdk::rpc::telemetry::EulerAngle*>(value); + _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value); if (value != nullptr) { _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse.attitude_euler) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) } -inline ::mavsdk::rpc::telemetry::EulerAngle* CameraAttitudeEulerResponse::release_attitude_euler() { +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::release_attitude_angular_velocity_body() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::EulerAngle* released = _impl_.attitude_euler_; - _impl_.attitude_euler_ = nullptr; + ::mavsdk::rpc::telemetry::AngularVelocityBody* released = _impl_.attitude_angular_velocity_body_; + _impl_.attitude_angular_velocity_body_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -28753,38 +27175,38 @@ inline ::mavsdk::rpc::telemetry::EulerAngle* CameraAttitudeEulerResponse::releas #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::telemetry::EulerAngle* CameraAttitudeEulerResponse::unsafe_arena_release_attitude_euler() { +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::unsafe_arena_release_attitude_angular_velocity_body() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse.attitude_euler) + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::EulerAngle* temp = _impl_.attitude_euler_; - _impl_.attitude_euler_ = nullptr; + ::mavsdk::rpc::telemetry::AngularVelocityBody* temp = _impl_.attitude_angular_velocity_body_; + _impl_.attitude_angular_velocity_body_ = nullptr; return temp; } -inline ::mavsdk::rpc::telemetry::EulerAngle* CameraAttitudeEulerResponse::_internal_mutable_attitude_euler() { +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::_internal_mutable_attitude_angular_velocity_body() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.attitude_euler_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::EulerAngle>(GetArena()); - _impl_.attitude_euler_ = reinterpret_cast<::mavsdk::rpc::telemetry::EulerAngle*>(p); + if (_impl_.attitude_angular_velocity_body_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityBody>(GetArena()); + _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(p); } - return _impl_.attitude_euler_; + return _impl_.attitude_angular_velocity_body_; } -inline ::mavsdk::rpc::telemetry::EulerAngle* CameraAttitudeEulerResponse::mutable_attitude_euler() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::telemetry::EulerAngle* _msg = _internal_mutable_attitude_euler(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse.attitude_euler) +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::mutable_attitude_angular_velocity_body() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::telemetry::AngularVelocityBody* _msg = _internal_mutable_attitude_angular_velocity_body(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) return _msg; } -inline void CameraAttitudeEulerResponse::set_allocated_attitude_euler(::mavsdk::rpc::telemetry::EulerAngle* value) { +inline void AttitudeAngularVelocityBodyResponse::set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::telemetry::EulerAngle*>(_impl_.attitude_euler_); + delete reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(_impl_.attitude_angular_velocity_body_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::EulerAngle*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -28793,8 +27215,8 @@ inline void CameraAttitudeEulerResponse::set_allocated_attitude_euler(::mavsdk:: _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.attitude_euler_ = reinterpret_cast<::mavsdk::rpc::telemetry::EulerAngle*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse.attitude_euler) + _impl_.attitude_angular_velocity_body_ = reinterpret_cast<::mavsdk::rpc::telemetry::AngularVelocityBody*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) } // ------------------------------------------------------------------- @@ -31988,260 +30410,6 @@ inline void SetRateAttitudeAngularVelocityBodyResponse::set_allocated_telemetry_ // ------------------------------------------------------------------- -// SetRateCameraAttitudeQuaternionRequest - -// double rate_hz = 1; -inline void SetRateCameraAttitudeQuaternionRequest::clear_rate_hz() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.rate_hz_ = 0; -} -inline double SetRateCameraAttitudeQuaternionRequest::rate_hz() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest.rate_hz) - return _internal_rate_hz(); -} -inline void SetRateCameraAttitudeQuaternionRequest::set_rate_hz(double value) { - _internal_set_rate_hz(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionRequest.rate_hz) -} -inline double SetRateCameraAttitudeQuaternionRequest::_internal_rate_hz() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.rate_hz_; -} -inline void SetRateCameraAttitudeQuaternionRequest::_internal_set_rate_hz(double value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.rate_hz_ = value; -} - -// ------------------------------------------------------------------- - -// SetRateCameraAttitudeQuaternionResponse - -// .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; -inline bool SetRateCameraAttitudeQuaternionResponse::has_telemetry_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.telemetry_result_ != nullptr); - return value; -} -inline void SetRateCameraAttitudeQuaternionResponse::clear_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.telemetry_result_ != nullptr) _impl_.telemetry_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeQuaternionResponse::_internal_telemetry_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::telemetry::TelemetryResult* p = _impl_.telemetry_result_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_TelemetryResult_default_instance_); -} -inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeQuaternionResponse::telemetry_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse.telemetry_result) - return _internal_telemetry_result(); -} -inline void SetRateCameraAttitudeQuaternionResponse::unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.telemetry_result_); - } - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse.telemetry_result) -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeQuaternionResponse::release_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::TelemetryResult* released = _impl_.telemetry_result_; - _impl_.telemetry_result_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeQuaternionResponse::unsafe_arena_release_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse.telemetry_result) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::TelemetryResult* temp = _impl_.telemetry_result_; - _impl_.telemetry_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeQuaternionResponse::_internal_mutable_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.telemetry_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(GetArena()); - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(p); - } - return _impl_.telemetry_result_; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeQuaternionResponse::mutable_telemetry_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::telemetry::TelemetryResult* _msg = _internal_mutable_telemetry_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse.telemetry_result) - return _msg; -} -inline void SetRateCameraAttitudeQuaternionResponse::set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(_impl_.telemetry_result_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.SetRateCameraAttitudeQuaternionResponse.telemetry_result) -} - -// ------------------------------------------------------------------- - -// SetRateCameraAttitudeRequest - -// double rate_hz = 1; -inline void SetRateCameraAttitudeRequest::clear_rate_hz() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.rate_hz_ = 0; -} -inline double SetRateCameraAttitudeRequest::rate_hz() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest.rate_hz) - return _internal_rate_hz(); -} -inline void SetRateCameraAttitudeRequest::set_rate_hz(double value) { - _internal_set_rate_hz(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.SetRateCameraAttitudeRequest.rate_hz) -} -inline double SetRateCameraAttitudeRequest::_internal_rate_hz() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.rate_hz_; -} -inline void SetRateCameraAttitudeRequest::_internal_set_rate_hz(double value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.rate_hz_ = value; -} - -// ------------------------------------------------------------------- - -// SetRateCameraAttitudeResponse - -// .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; -inline bool SetRateCameraAttitudeResponse::has_telemetry_result() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.telemetry_result_ != nullptr); - return value; -} -inline void SetRateCameraAttitudeResponse::clear_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.telemetry_result_ != nullptr) _impl_.telemetry_result_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; -} -inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeResponse::_internal_telemetry_result() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::telemetry::TelemetryResult* p = _impl_.telemetry_result_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry::_TelemetryResult_default_instance_); -} -inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateCameraAttitudeResponse::telemetry_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse.telemetry_result) - return _internal_telemetry_result(); -} -inline void SetRateCameraAttitudeResponse::unsafe_arena_set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.telemetry_result_); - } - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value); - if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse.telemetry_result) -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeResponse::release_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::TelemetryResult* released = _impl_.telemetry_result_; - _impl_.telemetry_result_ = nullptr; -#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE - auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - if (GetArena() == nullptr) { - delete old; - } -#else // PROTOBUF_FORCE_COPY_IN_RELEASE - if (GetArena() != nullptr) { - released = ::google::protobuf::internal::DuplicateIfNonNull(released); - } -#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE - return released; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeResponse::unsafe_arena_release_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse.telemetry_result) - - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry::TelemetryResult* temp = _impl_.telemetry_result_; - _impl_.telemetry_result_ = nullptr; - return temp; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeResponse::_internal_mutable_telemetry_result() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.telemetry_result_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(GetArena()); - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(p); - } - return _impl_.telemetry_result_; -} -inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateCameraAttitudeResponse::mutable_telemetry_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::telemetry::TelemetryResult* _msg = _internal_mutable_telemetry_result(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse.telemetry_result) - return _msg; -} -inline void SetRateCameraAttitudeResponse::set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* value) { - ::google::protobuf::Arena* message_arena = GetArena(); - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(_impl_.telemetry_result_); - } - - if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value)->GetArena(); - if (message_arena != submessage_arena) { - value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); - } - _impl_._has_bits_[0] |= 0x00000001u; - } else { - _impl_._has_bits_[0] &= ~0x00000001u; - } - - _impl_.telemetry_result_ = reinterpret_cast<::mavsdk::rpc::telemetry::TelemetryResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.SetRateCameraAttitudeResponse.telemetry_result) -} - -// ------------------------------------------------------------------- - // SetRateVelocityNedRequest // double rate_hz = 1; diff --git a/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h b/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h index d9c650c74d..aaf4e7be91 100644 --- a/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h @@ -1733,90 +1733,6 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv return grpc::Status::OK; } - grpc::Status SubscribeCameraAttitudeQuaternion( - grpc::ServerContext* /* context */, - const mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* /* request */, - grpc::ServerWriter* writer) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - return grpc::Status::OK; - } - - auto stream_closed_promise = std::make_shared>(); - auto stream_closed_future = stream_closed_promise->get_future(); - register_stream_stop_promise(stream_closed_promise); - - auto is_finished = std::make_shared(false); - auto subscribe_mutex = std::make_shared(); - - const mavsdk::Telemetry::CameraAttitudeQuaternionHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_camera_attitude_quaternion( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::Telemetry::Quaternion camera_attitude_quaternion) { - rpc::telemetry::CameraAttitudeQuaternionResponse rpc_response; - - rpc_response.set_allocated_attitude_quaternion( - translateToRpcQuaternion(camera_attitude_quaternion).release()); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_camera_attitude_quaternion(handle); - - *is_finished = true; - unregister_stream_stop_promise(stream_closed_promise); - stream_closed_promise->set_value(); - } - }); - - stream_closed_future.wait(); - std::unique_lock lock(*subscribe_mutex); - *is_finished = true; - - return grpc::Status::OK; - } - - grpc::Status SubscribeCameraAttitudeEuler( - grpc::ServerContext* /* context */, - const mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* /* request */, - grpc::ServerWriter* writer) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - return grpc::Status::OK; - } - - auto stream_closed_promise = std::make_shared>(); - auto stream_closed_future = stream_closed_promise->get_future(); - register_stream_stop_promise(stream_closed_promise); - - auto is_finished = std::make_shared(false); - auto subscribe_mutex = std::make_shared(); - - const mavsdk::Telemetry::CameraAttitudeEulerHandle handle = - _lazy_plugin.maybe_plugin()->subscribe_camera_attitude_euler( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::Telemetry::EulerAngle camera_attitude_euler) { - rpc::telemetry::CameraAttitudeEulerResponse rpc_response; - - rpc_response.set_allocated_attitude_euler( - translateToRpcEulerAngle(camera_attitude_euler).release()); - - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_camera_attitude_euler(handle); - - *is_finished = true; - unregister_stream_stop_promise(stream_closed_promise); - stream_closed_promise->set_value(); - } - }); - - stream_closed_future.wait(); - std::unique_lock lock(*subscribe_mutex); - *is_finished = true; - - return grpc::Status::OK; - } - grpc::Status SubscribeVelocityNed( grpc::ServerContext* /* context */, const mavsdk::rpc::telemetry::SubscribeVelocityNedRequest* /* request */, @@ -2966,34 +2882,6 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv return grpc::Status::OK; } - grpc::Status SetRateCameraAttitude( - grpc::ServerContext* /* context */, - const rpc::telemetry::SetRateCameraAttitudeRequest* request, - rpc::telemetry::SetRateCameraAttitudeResponse* response) override - { - if (_lazy_plugin.maybe_plugin() == nullptr) { - if (response != nullptr) { - auto result = mavsdk::Telemetry::Result::NoSystem; - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - - if (request == nullptr) { - LogWarn() << "SetRateCameraAttitude sent with a null request! Ignoring..."; - return grpc::Status::OK; - } - - auto result = _lazy_plugin.maybe_plugin()->set_rate_camera_attitude(request->rate_hz()); - - if (response != nullptr) { - fillResponseWithResult(response, result); - } - - return grpc::Status::OK; - } - grpc::Status SetRateVelocityNed( grpc::ServerContext* /* context */, const rpc::telemetry::SetRateVelocityNedRequest* request, diff --git a/src/mavsdk_server/test/telemetry_service_impl_test.cpp b/src/mavsdk_server/test/telemetry_service_impl_test.cpp index 83eeb48f8a..312133086a 100644 --- a/src/mavsdk_server/test/telemetry_service_impl_test.cpp +++ b/src/mavsdk_server/test/telemetry_service_impl_test.cpp @@ -166,14 +166,6 @@ class TelemetryServiceImplTest : public ::testing::Test { createEulerAngle(const float roll_deg, const float pitch_deg, const float yaw_deg) const; std::future subscribeAttitudeEulerAsync(std::vector& euler_angles) const; - void checkSendsCameraAttitudeQuaternions(const std::vector& quaternions) const; - std::future - subscribeCameraAttitudeQuaternionAsync(std::vector& quaternions) const; - - void checkSendsCameraAttitudeEulerAngles(const std::vector& euler_angles) const; - std::future - subscribeCameraAttitudeEulerAsync(std::vector& euler_angles) const; - void checkSendsVelocityEvents(const std::vector& velocity_events) const; VelocityNed createVelocityNed(const float vel_north, const float vel_east, const float vel_down) const; @@ -1339,183 +1331,6 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeEuler) checkSendsAttitudeEulerAngles(euler_angles); } -TEST_F(TelemetryServiceImplTest, registersToTelemetryCameraAttitudeQuaternionAsync) -{ - EXPECT_CALL(*_telemetry, subscribe_camera_attitude_quaternion(_)).Times(1); - - std::vector quaternions; - auto quaternion_stream_future = subscribeCameraAttitudeQuaternionAsync(quaternions); - - _telemetry_service->stop(); - quaternion_stream_future.wait(); -} - -std::future TelemetryServiceImplTest::subscribeCameraAttitudeQuaternionAsync( - std::vector& quaternions) const -{ - return std::async(std::launch::async, [&]() { - grpc::ClientContext context; - mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest request; - auto response_reader = _stub->SubscribeCameraAttitudeQuaternion(&context, request); - - mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse response; - while (response_reader->Read(&response)) { - auto quaternion_rpc = response.attitude_quaternion(); - - Quaternion quaternion; - quaternion.w = quaternion_rpc.w(); - quaternion.x = quaternion_rpc.x(); - quaternion.y = quaternion_rpc.y(); - quaternion.z = quaternion_rpc.z(); - - quaternions.push_back(quaternion); - } - - response_reader->Finish(); - }); -} - -TEST_F(TelemetryServiceImplTest, doesNotSendCameraAttitudeQuaternionIfCallbackNotCalled) -{ - std::vector quaternions; - auto quaternion_stream_future = subscribeCameraAttitudeQuaternionAsync(quaternions); - - _telemetry_service->stop(); - quaternion_stream_future.wait(); - - EXPECT_EQ(0, quaternions.size()); -} - -TEST_F(TelemetryServiceImplTest, sendsOneCameraAttitudeQuaternion) -{ - std::vector quaternions; - quaternions.push_back(createQuaternion(0.1f, 0.2f, 0.3f, 0.4f)); - - checkSendsCameraAttitudeQuaternions(quaternions); -} - -void TelemetryServiceImplTest::checkSendsCameraAttitudeQuaternions( - const std::vector& quaternions) const -{ - std::promise subscription_promise; - auto subscription_future = subscription_promise.get_future(); - mavsdk::CallbackList attitude_quaternion_callbacks; - EXPECT_CALL(*_telemetry, subscribe_camera_attitude_quaternion(_)) - .WillOnce(SaveCallback(&attitude_quaternion_callbacks, &subscription_promise)); - - std::vector received_quaternions; - auto quaternion_stream_future = subscribeCameraAttitudeQuaternionAsync(received_quaternions); - subscription_future.wait(); - for (const auto& quaternion : quaternions) { - attitude_quaternion_callbacks(quaternion); - } - _telemetry_service->stop(); - quaternion_stream_future.wait(); - - ASSERT_EQ(quaternions.size(), received_quaternions.size()); - for (size_t i = 0; i < quaternions.size(); i++) { - EXPECT_EQ(quaternions.at(i), received_quaternions.at(i)); - } -} - -TEST_F(TelemetryServiceImplTest, sendsMultipleCameraAttitudeQuaternions) -{ - std::vector quaternions; - quaternions.push_back(createQuaternion(0.1f, 0.2f, 0.3f, 0.4f)); - quaternions.push_back(createQuaternion(2.1f, 0.4f, -2.2f, 0.3f)); - quaternions.push_back(createQuaternion(5.2f, 5.9f, 1.1f, 0.8f)); - - checkSendsCameraAttitudeQuaternions(quaternions); -} - -TEST_F(TelemetryServiceImplTest, registersToTelemetryCameraAttitudeEulerAsync) -{ - EXPECT_CALL(*_telemetry, subscribe_camera_attitude_euler(_)).Times(1); - - std::vector euler_angles; - auto euler_angle_stream_future = subscribeCameraAttitudeEulerAsync(euler_angles); - - _telemetry_service->stop(); - euler_angle_stream_future.wait(); -} - -std::future TelemetryServiceImplTest::subscribeCameraAttitudeEulerAsync( - std::vector& euler_angles) const -{ - return std::async(std::launch::async, [&]() { - grpc::ClientContext context; - mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest request; - auto response_reader = _stub->SubscribeCameraAttitudeEuler(&context, request); - - mavsdk::rpc::telemetry::CameraAttitudeEulerResponse response; - while (response_reader->Read(&response)) { - auto euler_angle_rpc = response.attitude_euler(); - - EulerAngle euler_angle; - euler_angle.roll_deg = euler_angle_rpc.roll_deg(); - euler_angle.pitch_deg = euler_angle_rpc.pitch_deg(); - euler_angle.yaw_deg = euler_angle_rpc.yaw_deg(); - - euler_angles.push_back(euler_angle); - } - - response_reader->Finish(); - }); -} - -TEST_F(TelemetryServiceImplTest, doesNotSendCameraAttitudeEulerIfCallbackNotCalled) -{ - std::vector euler_angles; - auto euler_angle_stream_future = subscribeCameraAttitudeEulerAsync(euler_angles); - - _telemetry_service->stop(); - euler_angle_stream_future.wait(); - - EXPECT_EQ(0, euler_angles.size()); -} - -TEST_F(TelemetryServiceImplTest, sendsOneCameraAttitudeEuler) -{ - std::vector euler_angles; - euler_angles.push_back(createEulerAngle(23.4f, 90.2f, 7.8f)); - - checkSendsCameraAttitudeEulerAngles(euler_angles); -} - -void TelemetryServiceImplTest::checkSendsCameraAttitudeEulerAngles( - const std::vector& euler_angles) const -{ - std::promise subscription_promise; - auto subscription_future = subscription_promise.get_future(); - mavsdk::CallbackList attitude_euler_angle_callbacks; - EXPECT_CALL(*_telemetry, subscribe_camera_attitude_euler(_)) - .WillOnce(SaveCallback(&attitude_euler_angle_callbacks, &subscription_promise)); - - std::vector received_euler_angles; - auto euler_angle_stream_future = subscribeCameraAttitudeEulerAsync(received_euler_angles); - subscription_future.wait(); - for (const auto& euler_angle : euler_angles) { - attitude_euler_angle_callbacks(euler_angle); - } - _telemetry_service->stop(); - euler_angle_stream_future.wait(); - - ASSERT_EQ(euler_angles.size(), received_euler_angles.size()); - for (size_t i = 0; i < euler_angles.size(); i++) { - EXPECT_EQ(euler_angles.at(i), received_euler_angles.at(i)); - } -} - -TEST_F(TelemetryServiceImplTest, sendsMultipleCameraAttitudeEuler) -{ - std::vector euler_angles; - euler_angles.push_back(createEulerAngle(12.2f, 11.8f, -54.2f)); - euler_angles.push_back(createEulerAngle(18.3f, 37.4f, -61.7f)); - euler_angles.push_back(createEulerAngle(6.3f, 34.11f, -36.5f)); - - checkSendsCameraAttitudeEulerAngles(euler_angles); -} - TEST_F(TelemetryServiceImplTest, registersToTelemetryVelocityNedAsync) { EXPECT_CALL(*_telemetry, subscribe_velocity_ned(_)).Times(1);