diff --git a/proto b/proto index 822dc55977..47317e3a29 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 822dc55977a3fd9dbd045151d21bdb4721d54455 +Subproject commit 47317e3a299da6ac82c26cffce9c4e7404ae7918 diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 6c6b90857a..a86e335d9e 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -32,6 +32,7 @@ static void print_position_velocity_ned(Telemetry::PositionVelocityNed position_ static void print_unix_epoch_time_us(uint64_t time_us); static void print_actuator_control_target(Telemetry::ActuatorControlTarget actuator_control_target); static void print_actuator_output_status(Telemetry::ActuatorOutputStatus actuator_output_status); +static void print_altitude(Telemetry::Altitude altitude); static bool _set_rate_error = false; static bool _received_position = false; @@ -55,6 +56,7 @@ static bool _received_rc_status = false; static bool _received_position_velocity_ned = false; static bool _received_actuator_control_target = false; static bool _received_actuator_output_status = false; +static bool _received_altitude = false; TEST_F(SitlTest, PX4TelemetryAsync) { @@ -119,6 +121,10 @@ TEST_F(SitlTest, PX4TelemetryAsync) telemetry->set_rate_ground_truth_async( 10.0, [](Telemetry::Result result) { return receive_result(result); }); + + telemetry->set_rate_altitude_async( + 10.0, [](Telemetry::Result result) { return receive_result(result); }); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); telemetry->subscribe_position([](Telemetry::Position position) { print_position(position); }); @@ -186,6 +192,8 @@ TEST_F(SitlTest, PX4TelemetryAsync) print_actuator_output_status(actuator_output_status); }); + telemetry->subscribe_altitude([](Telemetry::Altitude altitude) { print_altitude(altitude); }); + std::this_thread::sleep_for(std::chrono::seconds(10)); EXPECT_FALSE(_set_rate_error); @@ -206,6 +214,7 @@ TEST_F(SitlTest, PX4TelemetryAsync) EXPECT_TRUE(_received_imu); EXPECT_TRUE(_received_gps_info); EXPECT_TRUE(_received_battery); + EXPECT_TRUE(_received_altitude); // EXPECT_TRUE(_received_rc_status); // No RC is sent in SITL. EXPECT_TRUE(_received_position_velocity_ned); // EXPECT_TRUE(_received_actuator_control_target); TODO check is that sent in SITL. @@ -355,6 +364,17 @@ void print_position_velocity_ned(Telemetry::PositionVelocityNed position_velocit _received_position_velocity_ned = true; } +void print_altitude(Telemetry::Altitude altitude) +{ + std::cout << "altitude_monotonic: " << altitude.altitude_monotonic_m << "m, " + << "altitude_local" << altitude.altitude_local_m << "m, " + << "altitude_amsl" << altitude.altitude_amsl_m << "m, " + << "altitude_relative" << altitude.altitude_relative_m << "m, " + << "altitude_terrain" << altitude.altitude_terrain_m << "m" << std::endl; + + _received_altitude = true; +} + void print_unix_epoch_time_us(uint64_t time_us) { std::time_t time = time_us / 1000000; diff --git a/src/integration_tests/telemetry_sync.cpp b/src/integration_tests/telemetry_sync.cpp index e3aefbac7d..13451bf585 100644 --- a/src/integration_tests/telemetry_sync.cpp +++ b/src/integration_tests/telemetry_sync.cpp @@ -30,6 +30,7 @@ TEST_F(SitlTest, PX4TelemetrySync) EXPECT_EQ(telemetry->set_rate_actuator_control_target(10.0), Telemetry::Result::Success); EXPECT_EQ(telemetry->set_rate_fixedwing_metrics(10.0), Telemetry::Result::Success); EXPECT_EQ(telemetry->set_rate_ground_truth(10.0), Telemetry::Result::Success); + EXPECT_EQ(telemetry->set_rate_altitude(10.0), Telemetry::Result::Success); for (unsigned i = 0; i < 10; ++i) { std::cout << "Position: " << telemetry->position() << '\n'; @@ -46,6 +47,7 @@ TEST_F(SitlTest, PX4TelemetrySync) std::cout << "Flight mode: " << telemetry->flight_mode() << '\n'; std::cout << "Landed state: " << telemetry->landed_state() << "(in air: " << telemetry->in_air() << ")" << '\n'; + std::cout << "Altitude: " << telemetry->altitude() << '\n'; std::this_thread::sleep_for(std::chrono::milliseconds(500)); } diff --git a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h index dbe95da143..38ddb39f06 100644 --- a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -957,6 +957,33 @@ class Telemetry : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Telemetry::GpsGlobalOrigin const& gps_global_origin); + /** + * @brief Altitude message type + */ + struct Altitude { + float altitude_monotonic_m{float( + NAN)}; /**< @brief Altitude in meters is initialized on system boot and monotonic */ + float altitude_amsl_m{ + float(NAN)}; /**< @brief Altitude AMSL (above mean sea level) in meters */ + float altitude_local_m{float(NAN)}; /**< @brief Local altitude in meters */ + float altitude_relative_m{float(NAN)}; /**< @brief Altitude above home position in meters */ + float altitude_terrain_m{float(NAN)}; /**< @brief Altitude above terrain in meters */ + }; + + /** + * @brief Equal operator to compare two `Telemetry::Altitude` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const Telemetry::Altitude& lhs, const Telemetry::Altitude& rhs); + + /** + * @brief Stream operator to print information about a `Telemetry::Altitude`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Telemetry::Altitude const& altitude); + /** * @brief Possible results returned for telemetry requests. */ @@ -1881,6 +1908,33 @@ class Telemetry : public PluginBase { */ Heading heading() const; + /** + * @brief Callback type for subscribe_altitude. + */ + using AltitudeCallback = std::function; + + /** + * @brief Handle type for subscribe_altitude. + */ + using AltitudeHandle = Handle; + + /** + * @brief Subscribe to 'Altitude' updates. + */ + AltitudeHandle subscribe_altitude(const AltitudeCallback& callback); + + /** + * @brief Unsubscribe from subscribe_altitude + */ + void unsubscribe_altitude(AltitudeHandle handle); + + /** + * @brief Poll for 'Altitude' (blocking). + * + * @return One Altitude update. + */ + Altitude altitude() const; + /** * @brief Set rate to 'position' updates. * @@ -2265,6 +2319,22 @@ class Telemetry : public PluginBase { */ Result set_rate_distance_sensor(double rate_hz) const; + /** + * @brief Set rate to 'Altitude' updates. + * + * This function is non-blocking. See 'set_rate_altitude' for the blocking counterpart. + */ + void set_rate_altitude_async(double rate_hz, const ResultCallback callback); + + /** + * @brief Set rate to 'Altitude' updates. + * + * This function is blocking. See 'set_rate_altitude_async' for the non-blocking counterpart. + * + * @return Result of request. + */ + Result set_rate_altitude(double rate_hz) const; + /** * @brief Callback type for get_gps_global_origin_async. */ diff --git a/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h b/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h index a433014f16..0c3bb9e09a 100644 --- a/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h +++ b/src/mavsdk/plugins/telemetry/mocks/telemetry_mock.h @@ -116,6 +116,8 @@ class MockTelemetry { MOCK_CONST_METHOD1( subscribe_vtol_state, Telemetry::VtolStateHandle(Telemetry::VtolStateCallback)){}; MOCK_CONST_METHOD1(unsubscribe_vtol_state, void(Telemetry::VtolStateHandle)){}; + MOCK_CONST_METHOD1(subscribe_altitude, Telemetry::AltitudeHandle(Telemetry::AltitudeCallback)); + MOCK_CONST_METHOD1(unsubscribe_altitude, void(Telemetry::AltitudeHandle)); MOCK_METHOD1(set_rate_position, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_home, Telemetry::Result(double)){}; @@ -142,6 +144,7 @@ class MockTelemetry { MOCK_METHOD1(set_rate_raw_imu, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_unix_epoch_time, Telemetry::Result(double)){}; MOCK_METHOD1(set_rate_vtol_state, Telemetry::Result(double)){}; + MOCK_METHOD1(set_rate_altitude, Telemetry::Result(double)){}; MOCK_CONST_METHOD2(set_rate_position_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_home_async, void(double, Telemetry::ResultCallback)){}; @@ -171,7 +174,7 @@ class MockTelemetry { MOCK_CONST_METHOD2(set_rate_scaled_imu_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_raw_imu_async, void(double, Telemetry::ResultCallback)){}; MOCK_CONST_METHOD2(set_rate_unix_epoch_time_async, void(double, Telemetry::ResultCallback)){}; - + MOCK_CONST_METHOD2(set_rate_altitude_async, void(double, Telemetry::ResultCallback)){}; MOCK_METHOD0( get_gps_global_origin, std::pair()){}; MOCK_METHOD1(get_gps_global_origin_async, void(Telemetry::GetGpsGlobalOriginCallback)){}; diff --git a/src/mavsdk/plugins/telemetry/telemetry.cpp b/src/mavsdk/plugins/telemetry/telemetry.cpp index 62f6f53409..a55199c3c4 100644 --- a/src/mavsdk/plugins/telemetry/telemetry.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry.cpp @@ -38,6 +38,7 @@ using AngularVelocityFrd = Telemetry::AngularVelocityFrd; using MagneticFieldFrd = Telemetry::MagneticFieldFrd; using Imu = Telemetry::Imu; using GpsGlobalOrigin = Telemetry::GpsGlobalOrigin; +using Altitude = Telemetry::Altitude; Telemetry::Telemetry(System& system) : PluginBase(), _impl{std::make_unique(system)} {} @@ -556,6 +557,21 @@ Telemetry::Heading Telemetry::heading() const return _impl->heading(); } +Telemetry::AltitudeHandle Telemetry::subscribe_altitude(const AltitudeCallback& callback) +{ + return _impl->subscribe_altitude(callback); +} + +void Telemetry::unsubscribe_altitude(AltitudeHandle handle) +{ + _impl->unsubscribe_altitude(handle); +} + +Telemetry::Altitude Telemetry::altitude() const +{ + return _impl->altitude(); +} + void Telemetry::set_rate_position_async(double rate_hz, const ResultCallback callback) { _impl->set_rate_position_async(rate_hz, callback); @@ -787,6 +803,16 @@ Telemetry::Result Telemetry::set_rate_distance_sensor(double rate_hz) const return _impl->set_rate_distance_sensor(rate_hz); } +void Telemetry::set_rate_altitude_async(double rate_hz, const ResultCallback callback) +{ + _impl->set_rate_altitude_async(rate_hz, callback); +} + +Telemetry::Result Telemetry::set_rate_altitude(double rate_hz) const +{ + return _impl->set_rate_altitude(rate_hz); +} + void Telemetry::get_gps_global_origin_async(const GetGpsGlobalOriginCallback callback) { _impl->get_gps_global_origin_async(callback); @@ -1449,6 +1475,33 @@ std::ostream& operator<<(std::ostream& str, Telemetry::GpsGlobalOrigin const& gp return str; } +bool operator==(const Telemetry::Altitude& lhs, const Telemetry::Altitude& rhs) +{ + return ((std::isnan(rhs.altitude_monotonic_m) && std::isnan(lhs.altitude_monotonic_m)) || + rhs.altitude_monotonic_m == lhs.altitude_monotonic_m) && + ((std::isnan(rhs.altitude_amsl_m) && std::isnan(lhs.altitude_amsl_m)) || + rhs.altitude_amsl_m == lhs.altitude_amsl_m) && + ((std::isnan(rhs.altitude_local_m) && std::isnan(lhs.altitude_local_m)) || + rhs.altitude_local_m == lhs.altitude_local_m) && + ((std::isnan(rhs.altitude_relative_m) && std::isnan(lhs.altitude_relative_m)) || + rhs.altitude_relative_m == lhs.altitude_relative_m) && + ((std::isnan(rhs.altitude_terrain_m) && std::isnan(lhs.altitude_terrain_m)) || + rhs.altitude_terrain_m == lhs.altitude_terrain_m); +} + +std::ostream& operator<<(std::ostream& str, Telemetry::Altitude const& altitude) +{ + str << std::setprecision(15); + str << "altitude:" << '\n' << "{\n"; + str << " altitude_monotonic_m: " << altitude.altitude_monotonic_m << '\n'; + str << " altitude_amsl_m: " << altitude.altitude_amsl_m << '\n'; + str << " altitude_local_m: " << altitude.altitude_local_m << '\n'; + str << " altitude_relative_m: " << altitude.altitude_relative_m << '\n'; + str << " altitude_terrain_m: " << altitude.altitude_terrain_m << '\n'; + str << '}'; + return str; +} + std::ostream& operator<<(std::ostream& str, Telemetry::Result const& result) { switch (result) { diff --git a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp index bc7c2481bc..0db12e074b 100644 --- a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp @@ -39,6 +39,7 @@ template class CallbackList; template class CallbackList; template class CallbackList; template class CallbackList; +template class CallbackList; TelemetryImpl::TelemetryImpl(System& system) : PluginImplBase(system) { @@ -179,6 +180,11 @@ void TelemetryImpl::init() [this](const mavlink_message_t& message) { process_ground_truth(message); }, this); + _parent->register_mavlink_message_handler( + MAVLINK_MSG_ID_ALTITUDE, + [this](const mavlink_message_t& message) { process_altitude(message); }, + this); + _parent->register_param_changed_handler( [this](const std::string& name) { process_parameter_update(name); }, this); @@ -395,6 +401,12 @@ Telemetry::Result TelemetryImpl::set_rate_unix_epoch_time(double rate_hz) _parent->set_msg_rate(MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, rate_hz)); } +Telemetry::Result TelemetryImpl::set_rate_altitude(double rate_hz) +{ + return telemetry_result_from_command_result( + _parent->set_msg_rate(MAVLINK_MSG_ID_ALTITUDE, rate_hz)); +} + void TelemetryImpl::set_rate_position_velocity_ned_async( double rate_hz, Telemetry::ResultCallback callback) { @@ -449,6 +461,16 @@ void TelemetryImpl::set_rate_landed_state_async(double rate_hz, Telemetry::Resul }); } +void TelemetryImpl::set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback) +{ + _parent->set_msg_rate_async( + MAVLINK_MSG_ID_ALTITUDE, + rate_hz, + [callback](MavlinkCommandSender::Result command_result, float) { + command_result_callback(command_result, callback); + }); +} + void TelemetryImpl::set_rate_attitude_quaternion_async( double rate_hz, Telemetry::ResultCallback callback) { @@ -809,6 +831,25 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message [this](const auto& func) { _parent->call_user_callback(func); }); } +void TelemetryImpl::process_altitude(const mavlink_message_t& message) +{ + mavlink_altitude_t mavlink_altitude; + mavlink_msg_altitude_decode(&message, &mavlink_altitude); + + Telemetry::Altitude new_altitude; + new_altitude.altitude_monotonic_m = mavlink_altitude.altitude_monotonic; + new_altitude.altitude_amsl_m = mavlink_altitude.altitude_amsl; + new_altitude.altitude_local_m = mavlink_altitude.altitude_local; + new_altitude.altitude_relative_m = mavlink_altitude.altitude_relative; + new_altitude.altitude_terrain_m = mavlink_altitude.altitude_terrain; + + set_altitude(new_altitude); + + std::lock_guard lock(_subscription_mutex); + _altitude_subscriptions.queue( + altitude(), [this](const auto& func) { _parent->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 @@ -1719,6 +1760,18 @@ void TelemetryImpl::set_heading(Telemetry::Heading heading) _heading = heading; } +Telemetry::Altitude TelemetryImpl::altitude() const +{ + std::lock_guard lock(_altitude_mutex); + return _altitude; +} + +void TelemetryImpl::set_altitude(Telemetry::Altitude altitude) +{ + std::lock_guard lock(_altitude_mutex); + _altitude = altitude; +} + Telemetry::Position TelemetryImpl::home() const { std::lock_guard lock(_home_position_mutex); @@ -2543,6 +2596,19 @@ void TelemetryImpl::unsubscribe_heading(Telemetry::HeadingHandle handle) _heading_subscriptions.unsubscribe(handle); } +Telemetry::AltitudeHandle +TelemetryImpl::subscribe_altitude(const Telemetry::AltitudeCallback& callback) +{ + std::lock_guard lock(_subscription_mutex); + return _altitude_subscriptions.subscribe(callback); +} + +void TelemetryImpl::unsubscribe_altitude(Telemetry::AltitudeHandle handle) +{ + std::lock_guard lock(_subscription_mutex); + _altitude_subscriptions.unsubscribe(handle); +} + void TelemetryImpl::request_home_position_async() { MavlinkCommandSender::CommandLong command_request_message{}; diff --git a/src/mavsdk/plugins/telemetry/telemetry_impl.h b/src/mavsdk/plugins/telemetry/telemetry_impl.h index ad9f99d0b7..b1e61b8cb1 100644 --- a/src/mavsdk/plugins/telemetry/telemetry_impl.h +++ b/src/mavsdk/plugins/telemetry/telemetry_impl.h @@ -50,6 +50,7 @@ class TelemetryImpl : public PluginImplBase { Telemetry::Result set_rate_distance_sensor(double rate_hz); Telemetry::Result set_rate_scaled_pressure(double rate_hz); Telemetry::Result set_rate_unix_epoch_time(double rate_hz); + Telemetry::Result set_rate_altitude(double rate_hz); void set_rate_position_velocity_ned_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_position_async(double rate_hz, Telemetry::ResultCallback callback); @@ -75,6 +76,7 @@ class TelemetryImpl : public PluginImplBase { void set_rate_distance_sensor_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_scaled_pressure_async(double rate_hz, Telemetry::ResultCallback callback); void set_rate_unix_epoch_time_async(double rate_hz, Telemetry::ResultCallback callback); + void set_rate_altitude_async(double rate_hz, Telemetry::ResultCallback callback); void get_gps_global_origin_async(const Telemetry::GetGpsGlobalOriginCallback callback); std::pair get_gps_global_origin(); @@ -112,6 +114,7 @@ class TelemetryImpl : public PluginImplBase { Telemetry::ScaledPressure scaled_pressure() const; uint64_t unix_epoch_time() const; Telemetry::Heading heading() const; + Telemetry::Altitude altitude() const; Telemetry::PositionVelocityNedHandle subscribe_position_velocity_ned(const Telemetry::PositionVelocityNedCallback& callback); @@ -198,6 +201,8 @@ class TelemetryImpl : public PluginImplBase { void unsubscribe_scaled_pressure(Telemetry::ScaledPressureHandle handle); Telemetry::HeadingHandle subscribe_heading(const Telemetry::HeadingCallback& callback); void unsubscribe_heading(Telemetry::HeadingHandle handle); + Telemetry::AltitudeHandle subscribe_altitude(const Telemetry::AltitudeCallback& callback); + void unsubscribe_altitude(Telemetry::AltitudeHandle handle); TelemetryImpl(const TelemetryImpl&) = delete; TelemetryImpl& operator=(const TelemetryImpl&) = delete; @@ -238,6 +243,7 @@ class TelemetryImpl : public PluginImplBase { void set_distance_sensor(Telemetry::DistanceSensor& distance_sensor); void set_scaled_pressure(Telemetry::ScaledPressure& scaled_pressure); void set_heading(Telemetry::Heading heading); + void set_altitude(Telemetry::Altitude altitude); void process_position_velocity_ned(const mavlink_message_t& message); void process_global_position_int(const mavlink_message_t& message); @@ -263,6 +269,7 @@ class TelemetryImpl : public PluginImplBase { void process_odometry(const mavlink_message_t& message); void process_distance_sensor(const mavlink_message_t& message); void process_scaled_pressure(const mavlink_message_t& message); + void process_altitude(const mavlink_message_t& message); void receive_param_cal_gyro(MAVLinkParameters::Result result, int value); void receive_param_cal_accel(MAVLinkParameters::Result result, int value); void receive_param_cal_mag(MAVLinkParameters::Result result, int value); @@ -393,6 +400,9 @@ class TelemetryImpl : public PluginImplBase { mutable std::mutex _scaled_pressure_mutex{}; Telemetry::ScaledPressure _scaled_pressure{}; + mutable std::mutex _altitude_mutex{}; + Telemetry::Altitude _altitude{}; + mutable std::mutex _request_home_position_mutex{}; std::atomic _hitl_enabled{false}; @@ -431,6 +441,7 @@ class TelemetryImpl : public PluginImplBase { CallbackList _distance_sensor_subscriptions{}; CallbackList _scaled_pressure_subscriptions{}; CallbackList _heading_subscriptions{}; + CallbackList _altitude_subscriptions{}; // The velocity (former ground speed) and position are coupled to the same message, therefore, // we just use the faster between the two. 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 7e853ec570..bafed82062 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.cc @@ -57,6 +57,7 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeScaledPressure", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHeading", + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAltitude", "/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition", "/mavsdk.rpc.telemetry.TelemetryService/SetRateHome", "/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir", @@ -80,6 +81,7 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SetRateRawImu", "/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime", "/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor", + "/mavsdk.rpc.telemetry.TelemetryService/SetRateAltitude", "/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin", }; @@ -123,30 +125,32 @@ TelemetryService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& c , 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_SetRatePosition_(TelemetryService_method_names[33], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateHome_(TelemetryService_method_names[34], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateInAir_(TelemetryService_method_names[35], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateLandedState_(TelemetryService_method_names[36], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateVtolState_(TelemetryService_method_names[37], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateAttitudeQuaternion_(TelemetryService_method_names[38], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateAttitudeEuler_(TelemetryService_method_names[39], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateCameraAttitude_(TelemetryService_method_names[40], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateVelocityNed_(TelemetryService_method_names[41], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateGpsInfo_(TelemetryService_method_names[42], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateBattery_(TelemetryService_method_names[43], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateRcStatus_(TelemetryService_method_names[44], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateActuatorControlTarget_(TelemetryService_method_names[45], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateActuatorOutputStatus_(TelemetryService_method_names[46], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateOdometry_(TelemetryService_method_names[47], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRatePositionVelocityNed_(TelemetryService_method_names[48], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateGroundTruth_(TelemetryService_method_names[49], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateFixedwingMetrics_(TelemetryService_method_names[50], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateImu_(TelemetryService_method_names[51], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateScaledImu_(TelemetryService_method_names[52], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateRawImu_(TelemetryService_method_names[53], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateUnixEpochTime_(TelemetryService_method_names[54], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SetRateDistanceSensor_(TelemetryService_method_names[55], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_GetGpsGlobalOrigin_(TelemetryService_method_names[56], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, 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) {} ::grpc::ClientReader< ::mavsdk::rpc::telemetry::PositionResponse>* TelemetryService::Stub::SubscribePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribePositionRequest& request) { @@ -677,6 +681,22 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::HeadingResponse>* Telemetry return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::HeadingResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeHeading_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* TelemetryService::Stub::SubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::AltitudeResponse>::Create(channel_.get(), rpcmethod_SubscribeAltitude_, context, request); +} + +void TelemetryService::Stub::async::SubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AltitudeResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::AltitudeResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeAltitude_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* TelemetryService::Stub::AsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AltitudeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAltitude_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* TelemetryService::Stub::PrepareAsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AltitudeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAltitude_, context, request, false, nullptr); +} + ::grpc::Status TelemetryService::Stub::SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRatePosition_, context, request, response); } @@ -1206,6 +1226,29 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateDistanceSens return result; } +::grpc::Status TelemetryService::Stub::SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetRateAltitude_, context, request, response); +} + +void TelemetryService::Stub::async::SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRateAltitude_, context, request, response, std::move(f)); +} + +void TelemetryService::Stub::async::SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetRateAltitude_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* TelemetryService::Stub::PrepareAsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse, ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetRateAltitude_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* TelemetryService::Stub::AsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetRateAltitudeRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::Status TelemetryService::Stub::GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetGpsGlobalOrigin_, context, request, response); } @@ -1562,6 +1605,16 @@ TelemetryService::Service::Service() { }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( TelemetryService_method_names[33], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>( + [](TelemetryService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::telemetry::AltitudeResponse>* writer) { + return service->SubscribeAltitude(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryService_method_names[34], ::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, @@ -1571,7 +1624,7 @@ TelemetryService::Service::Service() { return service->SetRatePosition(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[34], + TelemetryService_method_names[35], ::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, @@ -1581,7 +1634,7 @@ TelemetryService::Service::Service() { return service->SetRateHome(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[35], + TelemetryService_method_names[36], ::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, @@ -1591,7 +1644,7 @@ TelemetryService::Service::Service() { return service->SetRateInAir(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[36], + TelemetryService_method_names[37], ::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, @@ -1601,7 +1654,7 @@ TelemetryService::Service::Service() { return service->SetRateLandedState(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[37], + TelemetryService_method_names[38], ::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, @@ -1611,7 +1664,7 @@ TelemetryService::Service::Service() { return service->SetRateVtolState(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[38], + TelemetryService_method_names[39], ::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, @@ -1621,7 +1674,7 @@ TelemetryService::Service::Service() { return service->SetRateAttitudeQuaternion(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[39], + TelemetryService_method_names[40], ::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, @@ -1631,7 +1684,7 @@ TelemetryService::Service::Service() { return service->SetRateAttitudeEuler(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[40], + 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, @@ -1641,7 +1694,7 @@ TelemetryService::Service::Service() { return service->SetRateCameraAttitude(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[41], + TelemetryService_method_names[42], ::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, @@ -1651,7 +1704,7 @@ TelemetryService::Service::Service() { return service->SetRateVelocityNed(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[42], + TelemetryService_method_names[43], ::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, @@ -1661,7 +1714,7 @@ TelemetryService::Service::Service() { return service->SetRateGpsInfo(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[43], + TelemetryService_method_names[44], ::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, @@ -1671,7 +1724,7 @@ TelemetryService::Service::Service() { return service->SetRateBattery(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[44], + TelemetryService_method_names[45], ::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, @@ -1681,7 +1734,7 @@ TelemetryService::Service::Service() { return service->SetRateRcStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[45], + TelemetryService_method_names[46], ::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, @@ -1691,7 +1744,7 @@ TelemetryService::Service::Service() { return service->SetRateActuatorControlTarget(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[46], + TelemetryService_method_names[47], ::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, @@ -1701,7 +1754,7 @@ TelemetryService::Service::Service() { return service->SetRateActuatorOutputStatus(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[47], + TelemetryService_method_names[48], ::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, @@ -1711,7 +1764,7 @@ TelemetryService::Service::Service() { return service->SetRateOdometry(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[48], + TelemetryService_method_names[49], ::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, @@ -1721,7 +1774,7 @@ TelemetryService::Service::Service() { return service->SetRatePositionVelocityNed(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[49], + TelemetryService_method_names[50], ::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, @@ -1731,7 +1784,7 @@ TelemetryService::Service::Service() { return service->SetRateGroundTruth(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[50], + TelemetryService_method_names[51], ::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, @@ -1741,7 +1794,7 @@ TelemetryService::Service::Service() { return service->SetRateFixedwingMetrics(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[51], + TelemetryService_method_names[52], ::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, @@ -1751,7 +1804,7 @@ TelemetryService::Service::Service() { return service->SetRateImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[52], + TelemetryService_method_names[53], ::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, @@ -1761,7 +1814,7 @@ TelemetryService::Service::Service() { return service->SetRateScaledImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[53], + TelemetryService_method_names[54], ::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, @@ -1771,7 +1824,7 @@ TelemetryService::Service::Service() { return service->SetRateRawImu(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[54], + TelemetryService_method_names[55], ::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, @@ -1781,7 +1834,7 @@ TelemetryService::Service::Service() { return service->SetRateUnixEpochTime(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[55], + TelemetryService_method_names[56], ::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, @@ -1791,7 +1844,17 @@ TelemetryService::Service::Service() { return service->SetRateDistanceSensor(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[56], + TelemetryService_method_names[57], + ::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, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* req, + ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* resp) { + return service->SetRateAltitude(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryService_method_names[58], ::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, @@ -2036,6 +2099,13 @@ ::grpc::Status TelemetryService::Service::SubscribeHeading(::grpc::ServerContext return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status TelemetryService::Service::SubscribeAltitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status TelemetryService::Service::SetRatePosition(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response) { (void) context; (void) request; @@ -2197,6 +2267,13 @@ ::grpc::Status TelemetryService::Service::SetRateDistanceSensor(::grpc::ServerCo return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status TelemetryService::Service::SetRateAltitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status TelemetryService::Service::GetGpsGlobalOrigin(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* 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 d3fc708373..e81877d982 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.grpc.pb.h @@ -370,6 +370,16 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::HeadingResponse>> PrepareAsyncSubscribeHeading(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::HeadingResponse>>(PrepareAsyncSubscribeHeadingRaw(context, request, cq)); } + // Subscribe to 'Altitude' updates. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>> SubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>>(SubscribeAltitudeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>> AsyncSubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>>(AsyncSubscribeAltitudeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>> PrepareAsyncSubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>>(PrepareAsyncSubscribeAltitudeRaw(context, request, cq)); + } // Set rate to 'position' updates. virtual ::grpc::Status SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRatePositionResponse>> AsyncSetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) { @@ -554,6 +564,14 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>> PrepareAsyncSetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>>(PrepareAsyncSetRateDistanceSensorRaw(context, request, cq)); } + // Set rate to 'Altitude' updates. + virtual ::grpc::Status SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>> AsyncSetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>>(AsyncSetRateAltitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>> PrepareAsyncSetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>>(PrepareAsyncSetRateAltitudeRaw(context, request, cq)); + } // Get the GPS location of where the estimator has been initialized. virtual ::grpc::Status GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>> AsyncGetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) { @@ -631,6 +649,8 @@ class TelemetryService final { virtual void SubscribeScaledPressure(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::ScaledPressureResponse>* reactor) = 0; // Subscribe to 'Heading' updates. virtual void SubscribeHeading(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::HeadingResponse>* reactor) = 0; + // Subscribe to 'Altitude' updates. + virtual void SubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AltitudeResponse>* reactor) = 0; // Set rate to 'position' updates. virtual void SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response, std::function) = 0; virtual void SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -700,6 +720,9 @@ class TelemetryService final { // Set rate to 'Distance Sensor' updates. virtual void SetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response, std::function) = 0; virtual void SetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Set rate to 'Altitude' updates. + virtual void SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, std::function) = 0; + virtual void SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // Get the GPS location of where the estimator has been initialized. virtual void GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response, std::function) = 0; virtual void GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; @@ -807,6 +830,9 @@ class TelemetryService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::HeadingResponse>* SubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::HeadingResponse>* AsyncSubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::HeadingResponse>* PrepareAsyncSubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>* SubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>* AsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AltitudeResponse>* PrepareAsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRatePositionResponse>* AsyncSetRatePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRatePositionResponse>* PrepareAsyncSetRatePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateHomeResponse>* AsyncSetRateHomeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateHomeRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -853,6 +879,8 @@ class TelemetryService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>* PrepareAsyncSetRateUnixEpochTimeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* AsyncSetRateDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* PrepareAsyncSetRateDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* AsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* PrepareAsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* AsyncGetGpsGlobalOriginRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* PrepareAsyncGetGpsGlobalOriginRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) = 0; }; @@ -1156,6 +1184,15 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::HeadingResponse>> PrepareAsyncSubscribeHeading(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::HeadingResponse>>(PrepareAsyncSubscribeHeadingRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AltitudeResponse>> SubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AltitudeResponse>>(SubscribeAltitudeRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>> AsyncSubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>>(AsyncSubscribeAltitudeRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>> PrepareAsyncSubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>>(PrepareAsyncSubscribeAltitudeRaw(context, request, cq)); + } ::grpc::Status SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRatePositionResponse>> AsyncSetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRatePositionResponse>>(AsyncSetRatePositionRaw(context, request, cq)); @@ -1317,6 +1354,13 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>> PrepareAsyncSetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>>(PrepareAsyncSetRateDistanceSensorRaw(context, request, cq)); } + ::grpc::Status SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>> AsyncSetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>>(AsyncSetRateAltitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>> PrepareAsyncSetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>>(PrepareAsyncSetRateAltitudeRaw(context, request, cq)); + } ::grpc::Status GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>> AsyncGetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>>(AsyncGetGpsGlobalOriginRaw(context, request, cq)); @@ -1360,6 +1404,7 @@ class TelemetryService final { void SubscribeDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeDistanceSensorRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::DistanceSensorResponse>* reactor) override; void SubscribeScaledPressure(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::ScaledPressureResponse>* reactor) override; void SubscribeHeading(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::HeadingResponse>* reactor) override; + void SubscribeAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::telemetry::AltitudeResponse>* reactor) override; void SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response, std::function) override; void SetRatePosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetRateHome(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateHomeRequest* request, ::mavsdk::rpc::telemetry::SetRateHomeResponse* response, std::function) override; @@ -1406,6 +1451,8 @@ class TelemetryService final { void SetRateUnixEpochTime(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest* request, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response, std::function) override; void SetRateDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, std::function) override; + void SetRateAltitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response, std::function) override; void GetGpsGlobalOrigin(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: @@ -1518,6 +1565,9 @@ class TelemetryService final { ::grpc::ClientReader< ::mavsdk::rpc::telemetry::HeadingResponse>* SubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::HeadingResponse>* AsyncSubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::HeadingResponse>* PrepareAsyncSubscribeHeadingRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* SubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* AsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AltitudeResponse>* PrepareAsyncSubscribeAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRatePositionResponse>* AsyncSetRatePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRatePositionResponse>* PrepareAsyncSetRatePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateHomeResponse>* AsyncSetRateHomeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateHomeRequest& request, ::grpc::CompletionQueue* cq) override; @@ -1564,6 +1614,8 @@ class TelemetryService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>* PrepareAsyncSetRateUnixEpochTimeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* AsyncSetRateDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* PrepareAsyncSetRateDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* AsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* PrepareAsyncSetRateAltitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* AsyncGetGpsGlobalOriginRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>* PrepareAsyncGetGpsGlobalOriginRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SubscribePosition_; @@ -1599,6 +1651,7 @@ class TelemetryService final { const ::grpc::internal::RpcMethod rpcmethod_SubscribeDistanceSensor_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeScaledPressure_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeHeading_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeAltitude_; const ::grpc::internal::RpcMethod rpcmethod_SetRatePosition_; const ::grpc::internal::RpcMethod rpcmethod_SetRateHome_; const ::grpc::internal::RpcMethod rpcmethod_SetRateInAir_; @@ -1622,6 +1675,7 @@ class TelemetryService final { const ::grpc::internal::RpcMethod rpcmethod_SetRateRawImu_; const ::grpc::internal::RpcMethod rpcmethod_SetRateUnixEpochTime_; const ::grpc::internal::RpcMethod rpcmethod_SetRateDistanceSensor_; + const ::grpc::internal::RpcMethod rpcmethod_SetRateAltitude_; const ::grpc::internal::RpcMethod rpcmethod_GetGpsGlobalOrigin_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -1696,6 +1750,8 @@ class TelemetryService final { virtual ::grpc::Status SubscribeScaledPressure(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeScaledPressureRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ScaledPressureResponse>* writer); // Subscribe to 'Heading' updates. virtual ::grpc::Status SubscribeHeading(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::HeadingResponse>* writer); + // Subscribe to 'Altitude' updates. + virtual ::grpc::Status SubscribeAltitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* writer); // Set rate to 'position' updates. virtual ::grpc::Status SetRatePosition(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* request, ::mavsdk::rpc::telemetry::SetRatePositionResponse* response); // Set rate to 'home position' updates. @@ -1742,6 +1798,8 @@ class TelemetryService final { virtual ::grpc::Status SetRateUnixEpochTime(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest* request, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse* response); // Set rate to 'Distance Sensor' updates. virtual ::grpc::Status SetRateDistanceSensor(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* request, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* response); + // Set rate to 'Altitude' updates. + virtual ::grpc::Status SetRateAltitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* request, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* response); // Get the GPS location of where the estimator has been initialized. virtual ::grpc::Status GetGpsGlobalOrigin(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest* request, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse* response); }; @@ -2406,12 +2464,32 @@ class TelemetryService final { } }; template + class WithAsyncMethod_SubscribeAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeAltitude() { + ::grpc::Service::MarkMethodAsync(33); + } + ~WithAsyncMethod_SubscribeAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { + abort(); + 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); + } + }; + template class WithAsyncMethod_SetRatePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRatePosition() { - ::grpc::Service::MarkMethodAsync(33); + ::grpc::Service::MarkMethodAsync(34); } ~WithAsyncMethod_SetRatePosition() override { BaseClassMustBeDerivedFromService(this); @@ -2422,7 +2500,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(33, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2431,7 +2509,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateHome() { - ::grpc::Service::MarkMethodAsync(34); + ::grpc::Service::MarkMethodAsync(35); } ~WithAsyncMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); @@ -2442,7 +2520,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(34, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2451,7 +2529,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateInAir() { - ::grpc::Service::MarkMethodAsync(35); + ::grpc::Service::MarkMethodAsync(36); } ~WithAsyncMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -2462,7 +2540,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(35, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(36, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2471,7 +2549,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodAsync(36); + ::grpc::Service::MarkMethodAsync(37); } ~WithAsyncMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -2482,7 +2560,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(36, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(37, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2491,7 +2569,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodAsync(37); + ::grpc::Service::MarkMethodAsync(38); } ~WithAsyncMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -2502,7 +2580,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(37, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(38, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2511,7 +2589,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodAsync(38); + ::grpc::Service::MarkMethodAsync(39); } ~WithAsyncMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -2522,7 +2600,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(38, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(39, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2531,7 +2609,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodAsync(39); + ::grpc::Service::MarkMethodAsync(40); } ~WithAsyncMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -2542,7 +2620,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(39, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(40, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2551,7 +2629,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodAsync(40); + ::grpc::Service::MarkMethodAsync(41); } ~WithAsyncMethod_SetRateCameraAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -2562,7 +2640,7 @@ class TelemetryService final { 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(40, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(41, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2571,7 +2649,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodAsync(41); + ::grpc::Service::MarkMethodAsync(42); } ~WithAsyncMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2582,7 +2660,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(41, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(42, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2591,7 +2669,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodAsync(42); + ::grpc::Service::MarkMethodAsync(43); } ~WithAsyncMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -2602,7 +2680,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(42, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(43, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2611,7 +2689,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateBattery() { - ::grpc::Service::MarkMethodAsync(43); + ::grpc::Service::MarkMethodAsync(44); } ~WithAsyncMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -2622,7 +2700,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(43, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(44, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2631,7 +2709,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodAsync(44); + ::grpc::Service::MarkMethodAsync(45); } ~WithAsyncMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2642,7 +2720,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(44, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(45, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2651,7 +2729,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodAsync(45); + ::grpc::Service::MarkMethodAsync(46); } ~WithAsyncMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -2662,7 +2740,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(45, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(46, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2671,7 +2749,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodAsync(46); + ::grpc::Service::MarkMethodAsync(47); } ~WithAsyncMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -2682,7 +2760,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(46, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(47, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2691,7 +2769,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodAsync(47); + ::grpc::Service::MarkMethodAsync(48); } ~WithAsyncMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -2702,7 +2780,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(47, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(48, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2711,7 +2789,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodAsync(48); + ::grpc::Service::MarkMethodAsync(49); } ~WithAsyncMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -2722,7 +2800,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(48, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(49, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2731,7 +2809,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodAsync(49); + ::grpc::Service::MarkMethodAsync(50); } ~WithAsyncMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -2742,7 +2820,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(49, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(50, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2751,7 +2829,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodAsync(50); + ::grpc::Service::MarkMethodAsync(51); } ~WithAsyncMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -2762,7 +2840,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(50, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(51, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2771,7 +2849,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateImu() { - ::grpc::Service::MarkMethodAsync(51); + ::grpc::Service::MarkMethodAsync(52); } ~WithAsyncMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -2782,7 +2860,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(51, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(52, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2791,7 +2869,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodAsync(52); + ::grpc::Service::MarkMethodAsync(53); } ~WithAsyncMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -2802,7 +2880,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(52, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(53, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2811,7 +2889,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodAsync(53); + ::grpc::Service::MarkMethodAsync(54); } ~WithAsyncMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -2822,7 +2900,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(53, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(54, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2831,7 +2909,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodAsync(54); + ::grpc::Service::MarkMethodAsync(55); } ~WithAsyncMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -2842,7 +2920,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(54, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(55, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -2851,7 +2929,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodAsync(55); + ::grpc::Service::MarkMethodAsync(56); } ~WithAsyncMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -2862,7 +2940,27 @@ 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(55, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(56, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodAsync(57); + } + ~WithAsyncMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + 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); } }; template @@ -2871,7 +2969,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodAsync(56); + ::grpc::Service::MarkMethodAsync(58); } ~WithAsyncMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -2882,10 +2980,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(56, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(58, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; + typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_SubscribePosition : public BaseClass { private: @@ -3613,18 +3711,40 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeHeadingRequest* /*request*/) { return nullptr; } }; template + class WithCallbackMethod_SubscribeAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeAltitude() { + ::grpc::Service::MarkMethodCallback(33, + 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); })); + } + ~WithCallbackMethod_SubscribeAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::telemetry::AltitudeResponse>* SubscribeAltitude( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/) { return nullptr; } + }; + template class WithCallbackMethod_SetRatePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRatePosition() { - ::grpc::Service::MarkMethodCallback(33, + ::grpc::Service::MarkMethodCallback(34, 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(33); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(34); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3645,13 +3765,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateHome() { - ::grpc::Service::MarkMethodCallback(34, + ::grpc::Service::MarkMethodCallback(35, 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(34); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(35); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3672,13 +3792,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateInAir() { - ::grpc::Service::MarkMethodCallback(35, + ::grpc::Service::MarkMethodCallback(36, 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(35); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(36); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3699,13 +3819,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodCallback(36, + ::grpc::Service::MarkMethodCallback(37, 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(36); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(37); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3726,13 +3846,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodCallback(37, + ::grpc::Service::MarkMethodCallback(38, 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(37); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(38); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3753,13 +3873,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodCallback(38, + ::grpc::Service::MarkMethodCallback(39, 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(38); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(39); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3780,13 +3900,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodCallback(39, + ::grpc::Service::MarkMethodCallback(40, 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(39); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(40); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3807,13 +3927,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodCallback(40, + ::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(40); + ::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); } @@ -3834,13 +3954,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodCallback(41, + ::grpc::Service::MarkMethodCallback(42, 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(41); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(42); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3861,13 +3981,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodCallback(42, + ::grpc::Service::MarkMethodCallback(43, 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(42); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(43); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3888,13 +4008,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateBattery() { - ::grpc::Service::MarkMethodCallback(43, + ::grpc::Service::MarkMethodCallback(44, 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(43); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(44); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3915,13 +4035,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodCallback(44, + ::grpc::Service::MarkMethodCallback(45, 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(44); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(45); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3942,13 +4062,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodCallback(45, + ::grpc::Service::MarkMethodCallback(46, 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(45); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(46); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3969,13 +4089,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodCallback(46, + ::grpc::Service::MarkMethodCallback(47, 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(46); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(47); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -3996,13 +4116,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodCallback(47, + ::grpc::Service::MarkMethodCallback(48, 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(47); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(48); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4023,13 +4143,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodCallback(48, + ::grpc::Service::MarkMethodCallback(49, 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(48); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(49); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4050,13 +4170,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodCallback(49, + ::grpc::Service::MarkMethodCallback(50, 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(49); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(50); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4077,13 +4197,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodCallback(50, + ::grpc::Service::MarkMethodCallback(51, 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(50); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(51); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4104,13 +4224,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateImu() { - ::grpc::Service::MarkMethodCallback(51, + ::grpc::Service::MarkMethodCallback(52, 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(51); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(52); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4131,13 +4251,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodCallback(52, + ::grpc::Service::MarkMethodCallback(53, 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(52); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(53); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4158,13 +4278,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodCallback(53, + ::grpc::Service::MarkMethodCallback(54, 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(53); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(54); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4185,13 +4305,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodCallback(54, + ::grpc::Service::MarkMethodCallback(55, 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(54); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(55); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4212,13 +4332,13 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodCallback(55, + ::grpc::Service::MarkMethodCallback(56, 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(55); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(56); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4234,18 +4354,45 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse* /*response*/) { return nullptr; } }; template + class WithCallbackMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodCallback(57, + 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); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetRateAltitude( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) { return nullptr; } + }; + template class WithCallbackMethod_GetGpsGlobalOrigin : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodCallback(56, + ::grpc::Service::MarkMethodCallback(58, 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(56); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(58); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -4260,7 +4407,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 { @@ -4824,30 +4971,47 @@ class TelemetryService final { } }; template - class WithGenericMethod_SetRatePosition : public BaseClass { + class WithGenericMethod_SubscribeAltitude : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SetRatePosition() { + WithGenericMethod_SubscribeAltitude() { ::grpc::Service::MarkMethodGeneric(33); } - ~WithGenericMethod_SetRatePosition() override { + ~WithGenericMethod_SubscribeAltitude() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SetRatePosition(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRatePositionResponse* /*response*/) override { + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } }; template - class WithGenericMethod_SetRateHome : public BaseClass { + class WithGenericMethod_SetRatePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SetRateHome() { + WithGenericMethod_SetRatePosition() { ::grpc::Service::MarkMethodGeneric(34); } + ~WithGenericMethod_SetRatePosition() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRatePosition(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRatePositionRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRatePositionResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SetRateHome : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetRateHome() { + ::grpc::Service::MarkMethodGeneric(35); + } ~WithGenericMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); } @@ -4863,7 +5027,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateInAir() { - ::grpc::Service::MarkMethodGeneric(35); + ::grpc::Service::MarkMethodGeneric(36); } ~WithGenericMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -4880,7 +5044,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodGeneric(36); + ::grpc::Service::MarkMethodGeneric(37); } ~WithGenericMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -4897,7 +5061,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodGeneric(37); + ::grpc::Service::MarkMethodGeneric(38); } ~WithGenericMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -4914,7 +5078,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodGeneric(38); + ::grpc::Service::MarkMethodGeneric(39); } ~WithGenericMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -4931,7 +5095,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodGeneric(39); + ::grpc::Service::MarkMethodGeneric(40); } ~WithGenericMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -4948,7 +5112,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodGeneric(40); + ::grpc::Service::MarkMethodGeneric(41); } ~WithGenericMethod_SetRateCameraAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -4965,7 +5129,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodGeneric(41); + ::grpc::Service::MarkMethodGeneric(42); } ~WithGenericMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -4982,7 +5146,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodGeneric(42); + ::grpc::Service::MarkMethodGeneric(43); } ~WithGenericMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -4999,7 +5163,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateBattery() { - ::grpc::Service::MarkMethodGeneric(43); + ::grpc::Service::MarkMethodGeneric(44); } ~WithGenericMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -5016,7 +5180,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodGeneric(44); + ::grpc::Service::MarkMethodGeneric(45); } ~WithGenericMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5033,7 +5197,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodGeneric(45); + ::grpc::Service::MarkMethodGeneric(46); } ~WithGenericMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -5050,7 +5214,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodGeneric(46); + ::grpc::Service::MarkMethodGeneric(47); } ~WithGenericMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -5067,7 +5231,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodGeneric(47); + ::grpc::Service::MarkMethodGeneric(48); } ~WithGenericMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -5084,7 +5248,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodGeneric(48); + ::grpc::Service::MarkMethodGeneric(49); } ~WithGenericMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -5101,7 +5265,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodGeneric(49); + ::grpc::Service::MarkMethodGeneric(50); } ~WithGenericMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -5118,7 +5282,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodGeneric(50); + ::grpc::Service::MarkMethodGeneric(51); } ~WithGenericMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -5135,7 +5299,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateImu() { - ::grpc::Service::MarkMethodGeneric(51); + ::grpc::Service::MarkMethodGeneric(52); } ~WithGenericMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -5152,7 +5316,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodGeneric(52); + ::grpc::Service::MarkMethodGeneric(53); } ~WithGenericMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -5169,7 +5333,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodGeneric(53); + ::grpc::Service::MarkMethodGeneric(54); } ~WithGenericMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -5186,7 +5350,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodGeneric(54); + ::grpc::Service::MarkMethodGeneric(55); } ~WithGenericMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -5203,7 +5367,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodGeneric(55); + ::grpc::Service::MarkMethodGeneric(56); } ~WithGenericMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -5215,12 +5379,29 @@ class TelemetryService final { } }; template + class WithGenericMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodGeneric(57); + } + ~WithGenericMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_GetGpsGlobalOrigin : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodGeneric(56); + ::grpc::Service::MarkMethodGeneric(58); } ~WithGenericMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -5892,12 +6073,32 @@ class TelemetryService final { } }; template + class WithRawMethod_SubscribeAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeAltitude() { + ::grpc::Service::MarkMethodRaw(33); + } + ~WithRawMethod_SubscribeAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { + abort(); + 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); + } + }; + template class WithRawMethod_SetRatePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRatePosition() { - ::grpc::Service::MarkMethodRaw(33); + ::grpc::Service::MarkMethodRaw(34); } ~WithRawMethod_SetRatePosition() override { BaseClassMustBeDerivedFromService(this); @@ -5908,7 +6109,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(33, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(34, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -5917,7 +6118,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateHome() { - ::grpc::Service::MarkMethodRaw(34); + ::grpc::Service::MarkMethodRaw(35); } ~WithRawMethod_SetRateHome() override { BaseClassMustBeDerivedFromService(this); @@ -5928,7 +6129,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(34, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(35, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -5937,7 +6138,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateInAir() { - ::grpc::Service::MarkMethodRaw(35); + ::grpc::Service::MarkMethodRaw(36); } ~WithRawMethod_SetRateInAir() override { BaseClassMustBeDerivedFromService(this); @@ -5948,7 +6149,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(35, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(36, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -5957,7 +6158,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodRaw(36); + ::grpc::Service::MarkMethodRaw(37); } ~WithRawMethod_SetRateLandedState() override { BaseClassMustBeDerivedFromService(this); @@ -5968,7 +6169,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(36, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(37, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -5977,7 +6178,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodRaw(37); + ::grpc::Service::MarkMethodRaw(38); } ~WithRawMethod_SetRateVtolState() override { BaseClassMustBeDerivedFromService(this); @@ -5988,7 +6189,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(37, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(38, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -5997,7 +6198,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodRaw(38); + ::grpc::Service::MarkMethodRaw(39); } ~WithRawMethod_SetRateAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -6008,7 +6209,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(38, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(39, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6017,7 +6218,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodRaw(39); + ::grpc::Service::MarkMethodRaw(40); } ~WithRawMethod_SetRateAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -6028,7 +6229,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(39, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(40, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6037,7 +6238,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodRaw(40); + ::grpc::Service::MarkMethodRaw(41); } ~WithRawMethod_SetRateCameraAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -6048,7 +6249,7 @@ class TelemetryService final { 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(40, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(41, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6057,7 +6258,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodRaw(41); + ::grpc::Service::MarkMethodRaw(42); } ~WithRawMethod_SetRateVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -6068,7 +6269,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(41, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(42, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6077,7 +6278,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodRaw(42); + ::grpc::Service::MarkMethodRaw(43); } ~WithRawMethod_SetRateGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -6088,7 +6289,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(42, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(43, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6097,7 +6298,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateBattery() { - ::grpc::Service::MarkMethodRaw(43); + ::grpc::Service::MarkMethodRaw(44); } ~WithRawMethod_SetRateBattery() override { BaseClassMustBeDerivedFromService(this); @@ -6108,7 +6309,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(43, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(44, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6117,7 +6318,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodRaw(44); + ::grpc::Service::MarkMethodRaw(45); } ~WithRawMethod_SetRateRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -6128,7 +6329,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(44, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(45, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6137,7 +6338,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodRaw(45); + ::grpc::Service::MarkMethodRaw(46); } ~WithRawMethod_SetRateActuatorControlTarget() override { BaseClassMustBeDerivedFromService(this); @@ -6148,7 +6349,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(45, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(46, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6157,7 +6358,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodRaw(46); + ::grpc::Service::MarkMethodRaw(47); } ~WithRawMethod_SetRateActuatorOutputStatus() override { BaseClassMustBeDerivedFromService(this); @@ -6168,7 +6369,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(46, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(47, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6177,7 +6378,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodRaw(47); + ::grpc::Service::MarkMethodRaw(48); } ~WithRawMethod_SetRateOdometry() override { BaseClassMustBeDerivedFromService(this); @@ -6188,7 +6389,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(47, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(48, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6197,7 +6398,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodRaw(48); + ::grpc::Service::MarkMethodRaw(49); } ~WithRawMethod_SetRatePositionVelocityNed() override { BaseClassMustBeDerivedFromService(this); @@ -6208,7 +6409,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(48, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(49, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6217,7 +6418,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodRaw(49); + ::grpc::Service::MarkMethodRaw(50); } ~WithRawMethod_SetRateGroundTruth() override { BaseClassMustBeDerivedFromService(this); @@ -6228,7 +6429,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(49, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(50, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6237,7 +6438,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodRaw(50); + ::grpc::Service::MarkMethodRaw(51); } ~WithRawMethod_SetRateFixedwingMetrics() override { BaseClassMustBeDerivedFromService(this); @@ -6248,7 +6449,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(50, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(51, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6257,7 +6458,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateImu() { - ::grpc::Service::MarkMethodRaw(51); + ::grpc::Service::MarkMethodRaw(52); } ~WithRawMethod_SetRateImu() override { BaseClassMustBeDerivedFromService(this); @@ -6268,7 +6469,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(51, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(52, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6277,7 +6478,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodRaw(52); + ::grpc::Service::MarkMethodRaw(53); } ~WithRawMethod_SetRateScaledImu() override { BaseClassMustBeDerivedFromService(this); @@ -6288,7 +6489,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(52, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(53, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6297,7 +6498,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodRaw(53); + ::grpc::Service::MarkMethodRaw(54); } ~WithRawMethod_SetRateRawImu() override { BaseClassMustBeDerivedFromService(this); @@ -6308,7 +6509,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(53, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(54, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6317,7 +6518,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodRaw(54); + ::grpc::Service::MarkMethodRaw(55); } ~WithRawMethod_SetRateUnixEpochTime() override { BaseClassMustBeDerivedFromService(this); @@ -6328,7 +6529,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(54, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(55, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -6337,7 +6538,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodRaw(55); + ::grpc::Service::MarkMethodRaw(56); } ~WithRawMethod_SetRateDistanceSensor() override { BaseClassMustBeDerivedFromService(this); @@ -6348,7 +6549,27 @@ 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(55, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(56, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodRaw(57); + } + ~WithRawMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + 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); } }; template @@ -6357,7 +6578,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodRaw(56); + ::grpc::Service::MarkMethodRaw(58); } ~WithRawMethod_GetGpsGlobalOrigin() override { BaseClassMustBeDerivedFromService(this); @@ -6368,7 +6589,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(56, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(58, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -7098,12 +7319,34 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeAltitude() { + ::grpc::Service::MarkMethodRawCallback(33, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeAltitude(context, request); })); + } + ~WithRawCallbackMethod_SubscribeAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeAltitude( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SetRatePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRatePosition() { - ::grpc::Service::MarkMethodRawCallback(33, + ::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->SetRatePosition(context, request, response); })); @@ -7125,7 +7368,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateHome() { - ::grpc::Service::MarkMethodRawCallback(34, + ::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->SetRateHome(context, request, response); })); @@ -7147,7 +7390,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateInAir() { - ::grpc::Service::MarkMethodRawCallback(35, + ::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->SetRateInAir(context, request, response); })); @@ -7169,7 +7412,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodRawCallback(36, + ::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->SetRateLandedState(context, request, response); })); @@ -7191,7 +7434,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodRawCallback(37, + ::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->SetRateVtolState(context, request, response); })); @@ -7213,7 +7456,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodRawCallback(38, + ::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->SetRateAttitudeQuaternion(context, request, response); })); @@ -7235,7 +7478,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodRawCallback(39, + ::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->SetRateAttitudeEuler(context, request, response); })); @@ -7257,7 +7500,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodRawCallback(40, + ::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); })); @@ -7279,7 +7522,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(41, + ::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->SetRateVelocityNed(context, request, response); })); @@ -7301,7 +7544,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodRawCallback(42, + ::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->SetRateGpsInfo(context, request, response); })); @@ -7323,7 +7566,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateBattery() { - ::grpc::Service::MarkMethodRawCallback(43, + ::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->SetRateBattery(context, request, response); })); @@ -7345,7 +7588,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodRawCallback(44, + ::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->SetRateRcStatus(context, request, response); })); @@ -7367,7 +7610,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodRawCallback(45, + ::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->SetRateActuatorControlTarget(context, request, response); })); @@ -7389,7 +7632,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodRawCallback(46, + ::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->SetRateActuatorOutputStatus(context, request, response); })); @@ -7411,7 +7654,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodRawCallback(47, + ::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->SetRateOdometry(context, request, response); })); @@ -7433,7 +7676,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodRawCallback(48, + ::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->SetRatePositionVelocityNed(context, request, response); })); @@ -7455,7 +7698,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodRawCallback(49, + ::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->SetRateGroundTruth(context, request, response); })); @@ -7477,7 +7720,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodRawCallback(50, + ::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->SetRateFixedwingMetrics(context, request, response); })); @@ -7499,7 +7742,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateImu() { - ::grpc::Service::MarkMethodRawCallback(51, + ::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->SetRateImu(context, request, response); })); @@ -7521,7 +7764,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodRawCallback(52, + ::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->SetRateScaledImu(context, request, response); })); @@ -7543,7 +7786,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodRawCallback(53, + ::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->SetRateRawImu(context, request, response); })); @@ -7565,7 +7808,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodRawCallback(54, + ::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->SetRateUnixEpochTime(context, request, response); })); @@ -7587,7 +7830,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodRawCallback(55, + ::grpc::Service::MarkMethodRawCallback(56, 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); })); @@ -7604,12 +7847,34 @@ class TelemetryService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodRawCallback(57, + 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); })); + } + ~WithRawCallbackMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetRateAltitude( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_GetGpsGlobalOrigin : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodRawCallback(56, + ::grpc::Service::MarkMethodRawCallback(58, 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); })); @@ -7631,7 +7896,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRatePosition() { - ::grpc::Service::MarkMethodStreamed(33, + ::grpc::Service::MarkMethodStreamed(34, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionRequest, ::mavsdk::rpc::telemetry::SetRatePositionResponse>( [this](::grpc::ServerContext* context, @@ -7658,7 +7923,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateHome() { - ::grpc::Service::MarkMethodStreamed(34, + ::grpc::Service::MarkMethodStreamed(35, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateHomeRequest, ::mavsdk::rpc::telemetry::SetRateHomeResponse>( [this](::grpc::ServerContext* context, @@ -7685,7 +7950,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateInAir() { - ::grpc::Service::MarkMethodStreamed(35, + ::grpc::Service::MarkMethodStreamed(36, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateInAirRequest, ::mavsdk::rpc::telemetry::SetRateInAirResponse>( [this](::grpc::ServerContext* context, @@ -7712,7 +7977,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateLandedState() { - ::grpc::Service::MarkMethodStreamed(36, + ::grpc::Service::MarkMethodStreamed(37, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateLandedStateRequest, ::mavsdk::rpc::telemetry::SetRateLandedStateResponse>( [this](::grpc::ServerContext* context, @@ -7739,7 +8004,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateVtolState() { - ::grpc::Service::MarkMethodStreamed(37, + ::grpc::Service::MarkMethodStreamed(38, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVtolStateRequest, ::mavsdk::rpc::telemetry::SetRateVtolStateResponse>( [this](::grpc::ServerContext* context, @@ -7766,7 +8031,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateAttitudeQuaternion() { - ::grpc::Service::MarkMethodStreamed(38, + ::grpc::Service::MarkMethodStreamed(39, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse>( [this](::grpc::ServerContext* context, @@ -7793,7 +8058,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateAttitudeEuler() { - ::grpc::Service::MarkMethodStreamed(39, + ::grpc::Service::MarkMethodStreamed(40, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest, ::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse>( [this](::grpc::ServerContext* context, @@ -7820,7 +8085,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateCameraAttitude() { - ::grpc::Service::MarkMethodStreamed(40, + ::grpc::Service::MarkMethodStreamed(41, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest, ::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse>( [this](::grpc::ServerContext* context, @@ -7847,7 +8112,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateVelocityNed() { - ::grpc::Service::MarkMethodStreamed(41, + ::grpc::Service::MarkMethodStreamed(42, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRateVelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -7874,7 +8139,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateGpsInfo() { - ::grpc::Service::MarkMethodStreamed(42, + ::grpc::Service::MarkMethodStreamed(43, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGpsInfoRequest, ::mavsdk::rpc::telemetry::SetRateGpsInfoResponse>( [this](::grpc::ServerContext* context, @@ -7901,7 +8166,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateBattery() { - ::grpc::Service::MarkMethodStreamed(43, + ::grpc::Service::MarkMethodStreamed(44, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateBatteryRequest, ::mavsdk::rpc::telemetry::SetRateBatteryResponse>( [this](::grpc::ServerContext* context, @@ -7928,7 +8193,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateRcStatus() { - ::grpc::Service::MarkMethodStreamed(44, + ::grpc::Service::MarkMethodStreamed(45, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRcStatusRequest, ::mavsdk::rpc::telemetry::SetRateRcStatusResponse>( [this](::grpc::ServerContext* context, @@ -7955,7 +8220,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateActuatorControlTarget() { - ::grpc::Service::MarkMethodStreamed(45, + ::grpc::Service::MarkMethodStreamed(46, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>( [this](::grpc::ServerContext* context, @@ -7982,7 +8247,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateActuatorOutputStatus() { - ::grpc::Service::MarkMethodStreamed(46, + ::grpc::Service::MarkMethodStreamed(47, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>( [this](::grpc::ServerContext* context, @@ -8009,7 +8274,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateOdometry() { - ::grpc::Service::MarkMethodStreamed(47, + ::grpc::Service::MarkMethodStreamed(48, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateOdometryRequest, ::mavsdk::rpc::telemetry::SetRateOdometryResponse>( [this](::grpc::ServerContext* context, @@ -8036,7 +8301,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRatePositionVelocityNed() { - ::grpc::Service::MarkMethodStreamed(48, + ::grpc::Service::MarkMethodStreamed(49, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest, ::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse>( [this](::grpc::ServerContext* context, @@ -8063,7 +8328,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateGroundTruth() { - ::grpc::Service::MarkMethodStreamed(49, + ::grpc::Service::MarkMethodStreamed(50, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateGroundTruthRequest, ::mavsdk::rpc::telemetry::SetRateGroundTruthResponse>( [this](::grpc::ServerContext* context, @@ -8090,7 +8355,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateFixedwingMetrics() { - ::grpc::Service::MarkMethodStreamed(50, + ::grpc::Service::MarkMethodStreamed(51, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest, ::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse>( [this](::grpc::ServerContext* context, @@ -8117,7 +8382,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateImu() { - ::grpc::Service::MarkMethodStreamed(51, + ::grpc::Service::MarkMethodStreamed(52, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateImuRequest, ::mavsdk::rpc::telemetry::SetRateImuResponse>( [this](::grpc::ServerContext* context, @@ -8144,7 +8409,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateScaledImu() { - ::grpc::Service::MarkMethodStreamed(52, + ::grpc::Service::MarkMethodStreamed(53, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateScaledImuRequest, ::mavsdk::rpc::telemetry::SetRateScaledImuResponse>( [this](::grpc::ServerContext* context, @@ -8171,7 +8436,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateRawImu() { - ::grpc::Service::MarkMethodStreamed(53, + ::grpc::Service::MarkMethodStreamed(54, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateRawImuRequest, ::mavsdk::rpc::telemetry::SetRateRawImuResponse>( [this](::grpc::ServerContext* context, @@ -8198,7 +8463,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateUnixEpochTime() { - ::grpc::Service::MarkMethodStreamed(54, + ::grpc::Service::MarkMethodStreamed(55, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest, ::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse>( [this](::grpc::ServerContext* context, @@ -8225,7 +8490,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_SetRateDistanceSensor() { - ::grpc::Service::MarkMethodStreamed(55, + ::grpc::Service::MarkMethodStreamed(56, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest, ::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>( [this](::grpc::ServerContext* context, @@ -8247,12 +8512,39 @@ class TelemetryService final { virtual ::grpc::Status StreamedSetRateDistanceSensor(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest,::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse>* server_unary_streamer) = 0; }; template + class WithStreamedUnaryMethod_SetRateAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetRateAltitude() { + ::grpc::Service::MarkMethodStreamed(57, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::telemetry::SetRateAltitudeRequest, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* streamer) { + return this->StreamedSetRateAltitude(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetRateAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetRateAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* /*request*/, ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetRateAltitude(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest,::mavsdk::rpc::telemetry::SetRateAltitudeResponse>* server_unary_streamer) = 0; + }; + template class WithStreamedUnaryMethod_GetGpsGlobalOrigin : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_GetGpsGlobalOrigin() { - ::grpc::Service::MarkMethodStreamed(56, + ::grpc::Service::MarkMethodStreamed(58, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest, ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse>( [this](::grpc::ServerContext* context, @@ -8273,7 +8565,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: @@ -9165,8 +9457,35 @@ class TelemetryService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeHeading(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeHeadingRequest,::mavsdk::rpc::telemetry::HeadingResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > SplitStreamedService; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeAltitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeAltitude() { + ::grpc::Service::MarkMethodStreamed(33, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, ::mavsdk::rpc::telemetry::AltitudeResponse>* streamer) { + return this->StreamedSubscribeAltitude(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeAltitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeAltitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AltitudeResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // 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; }; } // 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 ba5640bf22..2ce1c5b618 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc @@ -785,6 +785,29 @@ struct HeadingResponseDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 HeadingResponseDefaultTypeInternal _HeadingResponse_default_instance_; +PROTOBUF_CONSTEXPR SubscribeAltitudeRequest::SubscribeAltitudeRequest( + ::_pbi::ConstantInitialized){} +struct SubscribeAltitudeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeAltitudeRequestDefaultTypeInternal() + : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeAltitudeRequestDefaultTypeInternal() {} + union { + SubscribeAltitudeRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeAltitudeRequestDefaultTypeInternal _SubscribeAltitudeRequest_default_instance_; +PROTOBUF_CONSTEXPR AltitudeResponse::AltitudeResponse( + ::_pbi::ConstantInitialized) + : altitude_(nullptr){} +struct AltitudeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR AltitudeResponseDefaultTypeInternal() + : _instance(::_pbi::ConstantInitialized{}) {} + ~AltitudeResponseDefaultTypeInternal() {} + union { + AltitudeResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AltitudeResponseDefaultTypeInternal _AltitudeResponse_default_instance_; PROTOBUF_CONSTEXPR SetRatePositionRequest::SetRatePositionRequest( ::_pbi::ConstantInitialized) : rate_hz_(0){} @@ -1421,6 +1444,30 @@ struct GetGpsGlobalOriginResponseDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetGpsGlobalOriginResponseDefaultTypeInternal _GetGpsGlobalOriginResponse_default_instance_; +PROTOBUF_CONSTEXPR SetRateAltitudeRequest::SetRateAltitudeRequest( + ::_pbi::ConstantInitialized) + : rate_hz_(0){} +struct SetRateAltitudeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetRateAltitudeRequestDefaultTypeInternal() + : _instance(::_pbi::ConstantInitialized{}) {} + ~SetRateAltitudeRequestDefaultTypeInternal() {} + union { + SetRateAltitudeRequest _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateAltitudeRequestDefaultTypeInternal _SetRateAltitudeRequest_default_instance_; +PROTOBUF_CONSTEXPR SetRateAltitudeResponse::SetRateAltitudeResponse( + ::_pbi::ConstantInitialized) + : telemetry_result_(nullptr){} +struct SetRateAltitudeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetRateAltitudeResponseDefaultTypeInternal() + : _instance(::_pbi::ConstantInitialized{}) {} + ~SetRateAltitudeResponseDefaultTypeInternal() {} + union { + SetRateAltitudeResponse _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetRateAltitudeResponseDefaultTypeInternal _SetRateAltitudeResponse_default_instance_; PROTOBUF_CONSTEXPR Position::Position( ::_pbi::ConstantInitialized) : latitude_deg_(0) @@ -1851,6 +1898,22 @@ struct GpsGlobalOriginDefaultTypeInternal { }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GpsGlobalOriginDefaultTypeInternal _GpsGlobalOrigin_default_instance_; +PROTOBUF_CONSTEXPR Altitude::Altitude( + ::_pbi::ConstantInitialized) + : altitude_monotonic_m_(0) + , altitude_amsl_m_(0) + , altitude_local_m_(0) + , altitude_relative_m_(0) + , altitude_terrain_m_(0){} +struct AltitudeDefaultTypeInternal { + PROTOBUF_CONSTEXPR AltitudeDefaultTypeInternal() + : _instance(::_pbi::ConstantInitialized{}) {} + ~AltitudeDefaultTypeInternal() {} + union { + Altitude _instance; + }; +}; +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AltitudeDefaultTypeInternal _Altitude_default_instance_; PROTOBUF_CONSTEXPR TelemetryResult::TelemetryResult( ::_pbi::ConstantInitialized) : result_str_(&::_pbi::fixed_address_empty_string, ::_pbi::ConstantInitialized{}) @@ -1868,7 +1931,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORIT } // namespace telemetry } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[149]; +static ::_pb::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[154]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_telemetry_2ftelemetry_2eproto[7]; static constexpr ::_pb::ServiceDescriptor const** file_level_service_descriptors_telemetry_2ftelemetry_2eproto = nullptr; @@ -2303,6 +2366,19 @@ const uint32_t TableStruct_telemetry_2ftelemetry_2eproto::offsets[] PROTOBUF_SEC ~0u, // no _inlined_string_donated_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::HeadingResponse, heading_deg_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeAltitudeRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AltitudeResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AltitudeResponse, altitude_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRatePositionRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -2674,6 +2750,20 @@ const uint32_t TableStruct_telemetry_2ftelemetry_2eproto::offsets[] PROTOBUF_SEC PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse, telemetry_result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse, gps_global_origin_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateAltitudeRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateAltitudeRequest, rate_hz_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateAltitudeResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SetRateAltitudeResponse, telemetry_result_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Position, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -2955,6 +3045,17 @@ const uint32_t TableStruct_telemetry_2ftelemetry_2eproto::offsets[] PROTOBUF_SEC PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::GpsGlobalOrigin, longitude_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::GpsGlobalOrigin, altitude_m_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, altitude_monotonic_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, altitude_amsl_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, altitude_local_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, altitude_relative_m_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Altitude, altitude_terrain_m_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::TelemetryResult, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -3030,89 +3131,94 @@ static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protode { 409, -1, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressureResponse)}, { 416, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHeadingRequest)}, { 422, -1, -1, sizeof(::mavsdk::rpc::telemetry::HeadingResponse)}, - { 429, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionRequest)}, - { 436, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionResponse)}, - { 443, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeRequest)}, - { 450, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeResponse)}, - { 457, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirRequest)}, - { 464, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirResponse)}, - { 471, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateRequest)}, - { 478, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateResponse)}, - { 485, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateRequest)}, - { 492, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateResponse)}, - { 499, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest)}, - { 506, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse)}, - { 513, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest)}, - { 520, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse)}, - { 527, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest)}, - { 534, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse)}, - { 541, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionRequest)}, - { 548, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionResponse)}, - { 555, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest)}, - { 562, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse)}, - { 569, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedRequest)}, - { 576, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedResponse)}, - { 583, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoRequest)}, - { 590, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoResponse)}, - { 597, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawGpsRequest)}, - { 604, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryRequest)}, - { 611, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryResponse)}, - { 618, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusRequest)}, - { 625, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusResponse)}, - { 632, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest)}, - { 639, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse)}, - { 646, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest)}, - { 653, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse)}, - { 660, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryRequest)}, - { 667, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryResponse)}, - { 674, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest)}, - { 681, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse)}, - { 688, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthRequest)}, - { 695, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthResponse)}, - { 702, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest)}, - { 709, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse)}, - { 716, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuRequest)}, - { 723, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuResponse)}, - { 730, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuRequest)}, - { 737, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuResponse)}, - { 744, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuRequest)}, - { 751, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuResponse)}, - { 758, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest)}, - { 765, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse)}, - { 772, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest)}, - { 779, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse)}, - { 786, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest)}, - { 792, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse)}, - { 800, -1, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, - { 810, -1, -1, sizeof(::mavsdk::rpc::telemetry::Heading)}, - { 817, -1, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, - { 828, -1, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, - { 838, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityBody)}, - { 847, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, - { 855, -1, -1, sizeof(::mavsdk::rpc::telemetry::RawGps)}, - { 875, -1, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, - { 884, -1, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, - { 897, -1, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, - { 906, -1, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, - { 914, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTarget)}, - { 922, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatus)}, - { 930, -1, -1, sizeof(::mavsdk::rpc::telemetry::Covariance)}, - { 937, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityBody)}, - { 946, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionBody)}, - { 955, -1, -1, sizeof(::mavsdk::rpc::telemetry::Odometry)}, - { 970, -1, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensor)}, - { 979, -1, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressure)}, - { 990, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionNed)}, - { 999, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNed)}, - { 1008, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNed)}, - { 1016, -1, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruth)}, - { 1025, -1, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetrics)}, - { 1034, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, - { 1043, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, - { 1052, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, - { 1061, -1, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, - { 1072, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, - { 1081, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, + { 429, -1, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAltitudeRequest)}, + { 435, -1, -1, sizeof(::mavsdk::rpc::telemetry::AltitudeResponse)}, + { 442, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionRequest)}, + { 449, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionResponse)}, + { 456, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeRequest)}, + { 463, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateHomeResponse)}, + { 470, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirRequest)}, + { 477, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateInAirResponse)}, + { 484, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateRequest)}, + { 491, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateLandedStateResponse)}, + { 498, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateRequest)}, + { 505, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVtolStateResponse)}, + { 512, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest)}, + { 519, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeEulerResponse)}, + { 526, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionRequest)}, + { 533, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeQuaternionResponse)}, + { 540, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest)}, + { 547, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse)}, + { 554, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionRequest)}, + { 561, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeQuaternionResponse)}, + { 568, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeRequest)}, + { 575, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateCameraAttitudeResponse)}, + { 582, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedRequest)}, + { 589, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateVelocityNedResponse)}, + { 596, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoRequest)}, + { 603, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGpsInfoResponse)}, + { 610, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawGpsRequest)}, + { 617, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryRequest)}, + { 624, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateBatteryResponse)}, + { 631, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusRequest)}, + { 638, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRcStatusResponse)}, + { 645, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest)}, + { 652, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse)}, + { 659, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest)}, + { 666, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse)}, + { 673, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryRequest)}, + { 680, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateOdometryResponse)}, + { 687, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedRequest)}, + { 694, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRatePositionVelocityNedResponse)}, + { 701, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthRequest)}, + { 708, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateGroundTruthResponse)}, + { 715, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsRequest)}, + { 722, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateFixedwingMetricsResponse)}, + { 729, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuRequest)}, + { 736, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateImuResponse)}, + { 743, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuRequest)}, + { 750, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateScaledImuResponse)}, + { 757, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuRequest)}, + { 764, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateRawImuResponse)}, + { 771, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeRequest)}, + { 778, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateUnixEpochTimeResponse)}, + { 785, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorRequest)}, + { 792, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateDistanceSensorResponse)}, + { 799, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginRequest)}, + { 805, -1, -1, sizeof(::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse)}, + { 813, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeRequest)}, + { 820, -1, -1, sizeof(::mavsdk::rpc::telemetry::SetRateAltitudeResponse)}, + { 827, -1, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, + { 837, -1, -1, sizeof(::mavsdk::rpc::telemetry::Heading)}, + { 844, -1, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, + { 855, -1, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, + { 865, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityBody)}, + { 874, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, + { 882, -1, -1, sizeof(::mavsdk::rpc::telemetry::RawGps)}, + { 902, -1, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, + { 911, -1, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, + { 924, -1, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, + { 933, -1, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, + { 941, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTarget)}, + { 949, -1, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatus)}, + { 957, -1, -1, sizeof(::mavsdk::rpc::telemetry::Covariance)}, + { 964, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityBody)}, + { 973, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionBody)}, + { 982, -1, -1, sizeof(::mavsdk::rpc::telemetry::Odometry)}, + { 997, -1, -1, sizeof(::mavsdk::rpc::telemetry::DistanceSensor)}, + { 1006, -1, -1, sizeof(::mavsdk::rpc::telemetry::ScaledPressure)}, + { 1017, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionNed)}, + { 1026, -1, -1, sizeof(::mavsdk::rpc::telemetry::VelocityNed)}, + { 1035, -1, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNed)}, + { 1043, -1, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruth)}, + { 1052, -1, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetrics)}, + { 1061, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, + { 1070, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, + { 1079, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, + { 1088, -1, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, + { 1099, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, + { 1108, -1, -1, sizeof(::mavsdk::rpc::telemetry::Altitude)}, + { 1119, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -3182,6 +3288,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_ScaledPressureResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SubscribeHeadingRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_HeadingResponse_default_instance_._instance, + &::mavsdk::rpc::telemetry::_SubscribeAltitudeRequest_default_instance_._instance, + &::mavsdk::rpc::telemetry::_AltitudeResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRatePositionRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRatePositionResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_SetRateHomeRequest_default_instance_._instance, @@ -3235,6 +3343,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_SetRateDistanceSensorResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_GetGpsGlobalOriginRequest_default_instance_._instance, &::mavsdk::rpc::telemetry::_GetGpsGlobalOriginResponse_default_instance_._instance, + &::mavsdk::rpc::telemetry::_SetRateAltitudeRequest_default_instance_._instance, + &::mavsdk::rpc::telemetry::_SetRateAltitudeResponse_default_instance_._instance, &::mavsdk::rpc::telemetry::_Position_default_instance_._instance, &::mavsdk::rpc::telemetry::_Heading_default_instance_._instance, &::mavsdk::rpc::telemetry::_Quaternion_default_instance_._instance, @@ -3264,6 +3374,7 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_MagneticFieldFrd_default_instance_._instance, &::mavsdk::rpc::telemetry::_Imu_default_instance_._instance, &::mavsdk::rpc::telemetry::_GpsGlobalOrigin_default_instance_._instance, + &::mavsdk::rpc::telemetry::_Altitude_default_instance_._instance, &::mavsdk::rpc::telemetry::_TelemetryResult_default_instance_._instance, }; @@ -3358,425 +3469,442 @@ const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] PROTOBUF_SE "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\")\n\026SetRatePositionRequest\022\017\n\007rate" - "_hz\030\001 \001(\001\"Z\n\027SetRatePositionResponse\022\?\n\020" - "telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tele" - "metry.TelemetryResult\"%\n\022SetRateHomeRequ" - "est\022\017\n\007rate_hz\030\001 \001(\001\"V\n\023SetRateHomeRespo" - "nse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.r" - "pc.telemetry.TelemetryResult\"&\n\023SetRateI" - "nAirRequest\022\017\n\007rate_hz\030\001 \001(\001\"W\n\024SetRateI" - "nAirResponse\022\?\n\020telemetry_result\030\001 \001(\0132%" - ".mavsdk.rpc.telemetry.TelemetryResult\",\n" - "\031SetRateLandedStateRequest\022\017\n\007rate_hz\030\001 " - "\001(\001\"]\n\032SetRateLandedStateResponse\022\?\n\020tel" - "emetry_result\030\001 \001(\0132%.mavsdk.rpc.telemet" - "ry.TelemetryResult\"*\n\027SetRateVtolStateRe" - "quest\022\017\n\007rate_hz\030\001 \001(\001\"[\n\030SetRateVtolSta" - "teResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.m" - "avsdk.rpc.telemetry.TelemetryResult\".\n\033S" - "etRateAttitudeEulerRequest\022\017\n\007rate_hz\030\001 " - "\001(\001\"_\n\034SetRateAttitudeEulerResponse\022\?\n\020t" - "elemetry_result\030\001 \001(\0132%.mavsdk.rpc.telem" - "etry.TelemetryResult\"3\n SetRateAttitudeQ" - "uaternionRequest\022\017\n\007rate_hz\030\001 \001(\001\"d\n!Set" - "RateAttitudeQuaternionResponse\022\?\n\020teleme" + "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)SetRateAttitudeAngula" - "rVelocityBodyRequest\022\017\n\007rate_hz\030\001 \001(\001\"m\n" - "*SetRateAttitudeAngularVelocityBodyRespo" - "nse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk.r" - "pc.telemetry.TelemetryResult\"9\n&SetRateC" - "ameraAttitudeQuaternionRequest\022\017\n\007rate_h" - "z\030\001 \001(\001\"j\n\'SetRateCameraAttitudeQuaterni" - "onResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.m" - "avsdk.rpc.telemetry.TelemetryResult\"/\n\034S" - "etRateCameraAttitudeRequest\022\017\n\007rate_hz\030\001" - " \001(\001\"`\n\035SetRateCameraAttitudeResponse\022\?\n" - "\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tel" - "emetry.TelemetryResult\",\n\031SetRateVelocit" - "yNedRequest\022\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRateV" - "elocityNedResponse\022\?\n\020telemetry_result\030\001" - " \001(\0132%.mavsdk.rpc.telemetry.TelemetryRes" - "ult\"(\n\025SetRateGpsInfoRequest\022\017\n\007rate_hz\030" - "\001 \001(\001\"Y\n\026SetRateGpsInfoResponse\022\?\n\020telem" - "etry_result\030\001 \001(\0132%.mavsdk.rpc.telemetry" - ".TelemetryResult\"\'\n\024SetRateRawGpsRequest" - "\022\017\n\007rate_hz\030\001 \001(\001\"(\n\025SetRateBatteryReque" - "st\022\017\n\007rate_hz\030\001 \001(\001\"Y\n\026SetRateBatteryRes" - "ponse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk" - ".rpc.telemetry.TelemetryResult\")\n\026SetRat" - "eRcStatusRequest\022\017\n\007rate_hz\030\001 \001(\001\"Z\n\027Set" - "RateRcStatusResponse\022\?\n\020telemetry_result" - "\030\001 \001(\0132%.mavsdk.rpc.telemetry.TelemetryR" - "esult\"6\n#SetRateActuatorControlTargetReq" - "uest\022\017\n\007rate_hz\030\001 \001(\001\"g\n$SetRateActuator" - "ControlTargetResponse\022\?\n\020telemetry_resul" + "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\"5\n\"SetRateActuatorOutputStatusReq" - "uest\022\017\n\007rate_hz\030\001 \001(\001\"f\n#SetRateActuator" - "OutputStatusResponse\022\?\n\020telemetry_result" - "\030\001 \001(\0132%.mavsdk.rpc.telemetry.TelemetryR" - "esult\")\n\026SetRateOdometryRequest\022\017\n\007rate_" - "hz\030\001 \001(\001\"Z\n\027SetRateOdometryResponse\022\?\n\020t" - "elemetry_result\030\001 \001(\0132%.mavsdk.rpc.telem" - "etry.TelemetryResult\"4\n!SetRatePositionV" - "elocityNedRequest\022\017\n\007rate_hz\030\001 \001(\001\"e\n\"Se" - "tRatePositionVelocityNedResponse\022\?\n\020tele" - "metry_result\030\001 \001(\0132%.mavsdk.rpc.telemetr" - "y.TelemetryResult\",\n\031SetRateGroundTruthR" - "equest\022\017\n\007rate_hz\030\001 \001(\001\"]\n\032SetRateGround" - "TruthResponse\022\?\n\020telemetry_result\030\001 \001(\0132" - "%.mavsdk.rpc.telemetry.TelemetryResult\"1" - "\n\036SetRateFixedwingMetricsRequest\022\017\n\007rate" - "_hz\030\001 \001(\001\"b\n\037SetRateFixedwingMetricsResp" - "onse\022\?\n\020telemetry_result\030\001 \001(\0132%.mavsdk." - "rpc.telemetry.TelemetryResult\"$\n\021SetRate" - "ImuRequest\022\017\n\007rate_hz\030\001 \001(\001\"U\n\022SetRateIm" - "uResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.ma" - "vsdk.rpc.telemetry.TelemetryResult\"*\n\027Se" - "tRateScaledImuRequest\022\017\n\007rate_hz\030\001 \001(\001\"[" - "\n\030SetRateScaledImuResponse\022\?\n\020telemetry_" - "result\030\001 \001(\0132%.mavsdk.rpc.telemetry.Tele" - "metryResult\"\'\n\024SetRateRawImuRequest\022\017\n\007r" - "ate_hz\030\001 \001(\001\"X\n\025SetRateRawImuResponse\022\?\n" - "\020telemetry_result\030\001 \001(\0132%.mavsdk.rpc.tel" - "emetry.TelemetryResult\".\n\033SetRateUnixEpo" - "chTimeRequest\022\017\n\007rate_hz\030\001 \001(\001\"_\n\034SetRat" - "eUnixEpochTimeResponse\022\?\n\020telemetry_resu" + "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" + "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" + "\?\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" "lt\030\001 \001(\0132%.mavsdk.rpc.telemetry.Telemetr" - "yResult\"/\n\034SetRateDistanceSensorRequest\022" - "\017\n\007rate_hz\030\001 \001(\001\"`\n\035SetRateDistanceSenso" - "rResponse\022\?\n\020telemetry_result\030\001 \001(\0132%.ma" - "vsdk.rpc.telemetry.TelemetryResult\"\033\n\031Ge" - "tGpsGlobalOriginRequest\"\237\001\n\032GetGpsGlobal" - "OriginResponse\022\?\n\020telemetry_result\030\001 \001(\013" - "2%.mavsdk.rpc.telemetry.TelemetryResult\022" - "@\n\021gps_global_origin\030\002 \001(\0132%.mavsdk.rpc." - "telemetry.GpsGlobalOrigin\"\225\001\n\010Position\022\035" - "\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitu" - "de_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolute_altitu" - "de_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\014time" - "stamp_us\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\003" - "NaN\022\030\n\007yaw_deg\030\003 \001(\002B\007\202\265\030\003NaN\022\024\n\014timesta" - "mp_us\030\004 \001(\004\"l\n\023AngularVelocityBody\022\033\n\nro" - "ll_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\003Na" - "N\"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.rpc.telem" - "etry.FixType\"\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_e" - "llipsoid_m\030\t \001(\002\022 \n\030horizontal_uncertain" - "ty_m\030\n \001(\002\022\036\n\026vertical_uncertainty_m\030\013 \001" - "(\002\022 \n\030velocity_uncertainty_m_s\030\014 \001(\002\022\037\n\027" - "heading_uncertainty_deg\030\r \001(\002\022\017\n\007yaw_deg" - "\030\016 \001(\002\"\\\n\007Battery\022\021\n\002id\030\003 \001(\rB\005\202\265\030\0010\022\032\n\t" - "voltage_v\030\001 \001(\002B\007\202\265\030\003NaN\022\"\n\021remaining_pe" - "rcent\030\002 \001(\002B\007\202\265\030\003NaN\"\271\002\n\006Health\022.\n\033is_gy" - "rometer_calibration_ok\030\001 \001(\010B\t\202\265\030\005false\022" - "2\n\037is_accelerometer_calibration_ok\030\002 \001(\010" - "B\t\202\265\030\005false\0221\n\036is_magnetometer_calibrati" - "on_ok\030\003 \001(\010B\t\202\265\030\005false\022\'\n\024is_local_posit" - "ion_ok\030\005 \001(\010B\t\202\265\030\005false\022(\n\025is_global_pos" - "ition_ok\030\006 \001(\010B\t\202\265\030\005false\022&\n\023is_home_pos" - "ition_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_avai" - "lable_once\030\001 \001(\010B\t\202\265\030\005false\022\037\n\014is_availa" - "ble\030\002 \001(\010B\t\202\265\030\005false\022(\n\027signal_strength_" - "percent\030\003 \001(\002B\007\202\265\030\003NaN\"N\n\nStatusText\0222\n\004" - "type\030\001 \001(\0162$.mavsdk.rpc.telemetry.Status" - "TextType\022\014\n\004text\030\002 \001(\t\"\?\n\025ActuatorContro" - "lTarget\022\024\n\005group\030\001 \001(\005B\005\202\265\030\0010\022\020\n\010control" - "s\030\002 \003(\002\"\?\n\024ActuatorOutputStatus\022\025\n\006activ" - "e\030\001 \001(\rB\005\202\265\030\0010\022\020\n\010actuator\030\002 \003(\002\"\'\n\nCova" - "riance\022\031\n\021covariance_matrix\030\001 \003(\002\";\n\014Vel" - "ocityBody\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\010Odomet" - "ry\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.te" - "lemetry.Odometry.MavFrame\0229\n\rposition_bo" - "dy\030\004 \001(\0132\".mavsdk.rpc.telemetry.Position" - "Body\022+\n\001q\030\005 \001(\0132 .mavsdk.rpc.telemetry.Q" - "uaternion\0229\n\rvelocity_body\030\006 \001(\0132\".mavsd" - "k.rpc.telemetry.VelocityBody\022H\n\025angular_" - "velocity_body\030\007 \001(\0132).mavsdk.rpc.telemet" - "ry.AngularVelocityBody\0229\n\017pose_covarianc" - "e\030\010 \001(\0132 .mavsdk.rpc.telemetry.Covarianc" - "e\022=\n\023velocity_covariance\030\t \001(\0132 .mavsdk." - "rpc.telemetry.Covariance\"j\n\010MavFrame\022\023\n\017" - "MAV_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\"\177\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\"\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" - "\"\241\002\n\017TelemetryResult\022<\n\006result\030\001 \001(\0162,.m" - "avsdk.rpc.telemetry.TelemetryResult.Resu" - "lt\022\022\n\nresult_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RES" - "ULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RES" - "ULT_NO_SYSTEM\020\002\022\033\n\027RESULT_CONNECTION_ERR" - "OR\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_U" - "NSUPPORTED\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_F" - "IX_2D\020\002\022\023\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE" - "_FIX_DGPS\020\004\022\026\n\022FIX_TYPE_RTK_FLOAT\020\005\022\026\n\022F" - "IX_TYPE_RTK_FIXED\020\006*\206\003\n\nFlightMode\022\027\n\023FL" - "IGHT_MODE_UNKNOWN\020\000\022\025\n\021FLIGHT_MODE_READY" - "\020\001\022\027\n\023FLIGHT_MODE_TAKEOFF\020\002\022\024\n\020FLIGHT_MO" - "DE_HOLD\020\003\022\027\n\023FLIGHT_MODE_MISSION\020\004\022 \n\034FL" - "IGHT_MODE_RETURN_TO_LAUNCH\020\005\022\024\n\020FLIGHT_M" - "ODE_LAND\020\006\022\030\n\024FLIGHT_MODE_OFFBOARD\020\007\022\031\n\025" - "FLIGHT_MODE_FOLLOW_ME\020\010\022\026\n\022FLIGHT_MODE_M" - "ANUAL\020\t\022\026\n\022FLIGHT_MODE_ALTCTL\020\n\022\026\n\022FLIGH" - "T_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" - "_RATTITUDE\020\016*\371\001\n\016StatusTextType\022\032\n\026STATU" - "S_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\030S" - "TATUS_TEXT_TYPE_WARNING\020\003\022\032\n\026STATUS_TEXT" - "_TYPE_ERROR\020\004\022\035\n\031STATUS_TEXT_TYPE_CRITIC" - "AL\020\005\022\032\n\026STATUS_TEXT_TYPE_ALERT\020\006\022\036\n\032STAT" - "US_TEXT_TYPE_EMERGENCY\020\007*\223\001\n\013LandedState" - "\022\030\n\024LANDED_STATE_UNKNOWN\020\000\022\032\n\026LANDED_STA" - "TE_ON_GROUND\020\001\022\027\n\023LANDED_STATE_IN_AIR\020\002\022" - "\033\n\027LANDED_STATE_TAKING_OFF\020\003\022\030\n\024LANDED_S" - "TATE_LANDING\020\004*\215\001\n\tVtolState\022\030\n\024VTOL_STA" - "TE_UNDEFINED\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\rVTOL_STATE_MC\020\003\022\021\n\rVTOL_STATE_FW\020\0042\236" - "7\n\020TelemetryService\022o\n\021SubscribePosition" - "\022..mavsdk.rpc.telemetry.SubscribePositio" - "nRequest\032&.mavsdk.rpc.telemetry.Position" - "Response\"\0000\001\022c\n\rSubscribeHome\022*.mavsdk.r" - "pc.telemetry.SubscribeHomeRequest\032\".mavs" - "dk.rpc.telemetry.HomeResponse\"\0000\001\022f\n\016Sub" - "scribeInAir\022+.mavsdk.rpc.telemetry.Subsc" - "ribeInAirRequest\032#.mavsdk.rpc.telemetry." - "InAirResponse\"\0000\001\022x\n\024SubscribeLandedStat" - "e\0221.mavsdk.rpc.telemetry.SubscribeLanded" - "StateRequest\032).mavsdk.rpc.telemetry.Land" - "edStateResponse\"\0000\001\022f\n\016SubscribeArmed\022+." - "mavsdk.rpc.telemetry.SubscribeArmedReque" - "st\032#.mavsdk.rpc.telemetry.ArmedResponse\"" - "\0000\001\022r\n\022SubscribeVtolState\022/.mavsdk.rpc.t" - "elemetry.SubscribeVtolStateRequest\032\'.mav" - "sdk.rpc.telemetry.VtolStateResponse\"\0000\001\022" - "\215\001\n\033SubscribeAttitudeQuaternion\0228.mavsdk" - ".rpc.telemetry.SubscribeAttitudeQuaterni" - "onRequest\0320.mavsdk.rpc.telemetry.Attitud" - "eQuaternionResponse\"\0000\001\022~\n\026SubscribeAtti" - "tudeEuler\0223.mavsdk.rpc.telemetry.Subscri" - "beAttitudeEulerRequest\032+.mavsdk.rpc.tele" - "metry.AttitudeEulerResponse\"\0000\001\022\250\001\n$Subs" - "cribeAttitudeAngularVelocityBody\022A.mavsd" - "k.rpc.telemetry.SubscribeAttitudeAngular" - "VelocityBodyRequest\0329.mavsdk.rpc.telemet" - "ry.AttitudeAngularVelocityBodyResponse\"\000" - "0\001\022\237\001\n!SubscribeCameraAttitudeQuaternion" - "\022>.mavsdk.rpc.telemetry.SubscribeCameraA" - "ttitudeQuaternionRequest\0326.mavsdk.rpc.te" - "lemetry.CameraAttitudeQuaternionResponse" - "\"\0000\001\022\220\001\n\034SubscribeCameraAttitudeEuler\0229." - "mavsdk.rpc.telemetry.SubscribeCameraAtti" - "tudeEulerRequest\0321.mavsdk.rpc.telemetry." - "CameraAttitudeEulerResponse\"\0000\001\022x\n\024Subsc" - "ribeVelocityNed\0221.mavsdk.rpc.telemetry.S" - "ubscribeVelocityNedRequest\032).mavsdk.rpc." - "telemetry.VelocityNedResponse\"\0000\001\022l\n\020Sub" - "scribeGpsInfo\022-.mavsdk.rpc.telemetry.Sub" - "scribeGpsInfoRequest\032%.mavsdk.rpc.teleme" - "try.GpsInfoResponse\"\0000\001\022i\n\017SubscribeRawG" - "ps\022,.mavsdk.rpc.telemetry.SubscribeRawGp" - "sRequest\032$.mavsdk.rpc.telemetry.RawGpsRe" - "sponse\"\0000\001\022l\n\020SubscribeBattery\022-.mavsdk." - "rpc.telemetry.SubscribeBatteryRequest\032%." - "mavsdk.rpc.telemetry.BatteryResponse\"\0000\001" - "\022u\n\023SubscribeFlightMode\0220.mavsdk.rpc.tel" - "emetry.SubscribeFlightModeRequest\032(.mavs" - "dk.rpc.telemetry.FlightModeResponse\"\0000\001\022" - "i\n\017SubscribeHealth\022,.mavsdk.rpc.telemetr" - "y.SubscribeHealthRequest\032$.mavsdk.rpc.te" - "lemetry.HealthResponse\"\0000\001\022o\n\021SubscribeR" - "cStatus\022..mavsdk.rpc.telemetry.Subscribe" - "RcStatusRequest\032&.mavsdk.rpc.telemetry.R" - "cStatusResponse\"\0000\001\022u\n\023SubscribeStatusTe" - "xt\0220.mavsdk.rpc.telemetry.SubscribeStatu" - "sTextRequest\032(.mavsdk.rpc.telemetry.Stat" - "usTextResponse\"\0000\001\022\226\001\n\036SubscribeActuator" - "ControlTarget\022;.mavsdk.rpc.telemetry.Sub" - "scribeActuatorControlTargetRequest\0323.mav" - "sdk.rpc.telemetry.ActuatorControlTargetR" - "esponse\"\0000\001\022\223\001\n\035SubscribeActuatorOutputS" - "tatus\022:.mavsdk.rpc.telemetry.SubscribeAc" - "tuatorOutputStatusRequest\0322.mavsdk.rpc.t" - "elemetry.ActuatorOutputStatusResponse\"\0000" - "\001\022o\n\021SubscribeOdometry\022..mavsdk.rpc.tele" - "metry.SubscribeOdometryRequest\032&.mavsdk." - "rpc.telemetry.OdometryResponse\"\0000\001\022\220\001\n\034S" - "ubscribePositionVelocityNed\0229.mavsdk.rpc" - ".telemetry.SubscribePositionVelocityNedR" - "equest\0321.mavsdk.rpc.telemetry.PositionVe" - "locityNedResponse\"\0000\001\022x\n\024SubscribeGround" - "Truth\0221.mavsdk.rpc.telemetry.SubscribeGr" - "oundTruthRequest\032).mavsdk.rpc.telemetry." - "GroundTruthResponse\"\0000\001\022\207\001\n\031SubscribeFix" - "edwingMetrics\0226.mavsdk.rpc.telemetry.Sub" - "scribeFixedwingMetricsRequest\032..mavsdk.r" - "pc.telemetry.FixedwingMetricsResponse\"\0000" - "\001\022`\n\014SubscribeImu\022).mavsdk.rpc.telemetry" - ".SubscribeImuRequest\032!.mavsdk.rpc.teleme" - "try.ImuResponse\"\0000\001\022r\n\022SubscribeScaledIm" - "u\022/.mavsdk.rpc.telemetry.SubscribeScaled" - "ImuRequest\032\'.mavsdk.rpc.telemetry.Scaled" - "ImuResponse\"\0000\001\022i\n\017SubscribeRawImu\022,.mav" - "sdk.rpc.telemetry.SubscribeRawImuRequest" - "\032$.mavsdk.rpc.telemetry.RawImuResponse\"\000" - "0\001\022x\n\024SubscribeHealthAllOk\0221.mavsdk.rpc." - "telemetry.SubscribeHealthAllOkRequest\032)." - "mavsdk.rpc.telemetry.HealthAllOkResponse" - "\"\0000\001\022~\n\026SubscribeUnixEpochTime\0223.mavsdk." - "rpc.telemetry.SubscribeUnixEpochTimeRequ" - "est\032+.mavsdk.rpc.telemetry.UnixEpochTime" - "Response\"\0000\001\022\201\001\n\027SubscribeDistanceSensor" - "\0224.mavsdk.rpc.telemetry.SubscribeDistanc" - "eSensorRequest\032,.mavsdk.rpc.telemetry.Di" - "stanceSensorResponse\"\0000\001\022\201\001\n\027SubscribeSc" - "aledPressure\0224.mavsdk.rpc.telemetry.Subs" - "cribeScaledPressureRequest\032,.mavsdk.rpc." - "telemetry.ScaledPressureResponse\"\0000\001\022l\n\020" - "SubscribeHeading\022-.mavsdk.rpc.telemetry." - "SubscribeHeadingRequest\032%.mavsdk.rpc.tel" - "emetry.HeadingResponse\"\0000\001\022p\n\017SetRatePos" - "ition\022,.mavsdk.rpc.telemetry.SetRatePosi" - "tionRequest\032-.mavsdk.rpc.telemetry.SetRa" - "tePositionResponse\"\000\022d\n\013SetRateHome\022(.ma" - "vsdk.rpc.telemetry.SetRateHomeRequest\032)." - "mavsdk.rpc.telemetry.SetRateHomeResponse" - "\"\000\022g\n\014SetRateInAir\022).mavsdk.rpc.telemetr" - "y.SetRateInAirRequest\032*.mavsdk.rpc.telem" - "etry.SetRateInAirResponse\"\000\022y\n\022SetRateLa" - "ndedState\022/.mavsdk.rpc.telemetry.SetRate" - "LandedStateRequest\0320.mavsdk.rpc.telemetr" - "y.SetRateLandedStateResponse\"\000\022s\n\020SetRat" - "eVtolState\022-.mavsdk.rpc.telemetry.SetRat" - "eVtolStateRequest\032..mavsdk.rpc.telemetry" - ".SetRateVtolStateResponse\"\000\022\216\001\n\031SetRateA" - "ttitudeQuaternion\0226.mavsdk.rpc.telemetry" - ".SetRateAttitudeQuaternionRequest\0327.mavs" - "dk.rpc.telemetry.SetRateAttitudeQuaterni" - "onResponse\"\000\022\177\n\024SetRateAttitudeEuler\0221.m" - "avsdk.rpc.telemetry.SetRateAttitudeEuler" - "Request\0322.mavsdk.rpc.telemetry.SetRateAt" - "titudeEulerResponse\"\000\022\202\001\n\025SetRateCameraA" - "ttitude\0222.mavsdk.rpc.telemetry.SetRateCa" - "meraAttitudeRequest\0323.mavsdk.rpc.telemet" - "ry.SetRateCameraAttitudeResponse\"\000\022y\n\022Se" - "tRateVelocityNed\022/.mavsdk.rpc.telemetry." - "SetRateVelocityNedRequest\0320.mavsdk.rpc.t" - "elemetry.SetRateVelocityNedResponse\"\000\022m\n" - "\016SetRateGpsInfo\022+.mavsdk.rpc.telemetry.S" - "etRateGpsInfoRequest\032,.mavsdk.rpc.teleme" - "try.SetRateGpsInfoResponse\"\000\022m\n\016SetRateB" - "attery\022+.mavsdk.rpc.telemetry.SetRateBat" - "teryRequest\032,.mavsdk.rpc.telemetry.SetRa" - "teBatteryResponse\"\000\022p\n\017SetRateRcStatus\022," - ".mavsdk.rpc.telemetry.SetRateRcStatusReq" - "uest\032-.mavsdk.rpc.telemetry.SetRateRcSta" - "tusResponse\"\000\022\227\001\n\034SetRateActuatorControl" - "Target\0229.mavsdk.rpc.telemetry.SetRateAct" - "uatorControlTargetRequest\032:.mavsdk.rpc.t" - "elemetry.SetRateActuatorControlTargetRes" - "ponse\"\000\022\224\001\n\033SetRateActuatorOutputStatus\022" - "8.mavsdk.rpc.telemetry.SetRateActuatorOu" - "tputStatusRequest\0329.mavsdk.rpc.telemetry" - ".SetRateActuatorOutputStatusResponse\"\000\022p" - "\n\017SetRateOdometry\022,.mavsdk.rpc.telemetry" - ".SetRateOdometryRequest\032-.mavsdk.rpc.tel" - "emetry.SetRateOdometryResponse\"\000\022\221\001\n\032Set" - "RatePositionVelocityNed\0227.mavsdk.rpc.tel" - "emetry.SetRatePositionVelocityNedRequest" - "\0328.mavsdk.rpc.telemetry.SetRatePositionV" - "elocityNedResponse\"\000\022y\n\022SetRateGroundTru" - "th\022/.mavsdk.rpc.telemetry.SetRateGroundT" - "ruthRequest\0320.mavsdk.rpc.telemetry.SetRa" - "teGroundTruthResponse\"\000\022\210\001\n\027SetRateFixed" - "wingMetrics\0224.mavsdk.rpc.telemetry.SetRa" - "teFixedwingMetricsRequest\0325.mavsdk.rpc.t" - "elemetry.SetRateFixedwingMetricsResponse" - "\"\000\022a\n\nSetRateImu\022\'.mavsdk.rpc.telemetry." - "SetRateImuRequest\032(.mavsdk.rpc.telemetry" - ".SetRateImuResponse\"\000\022s\n\020SetRateScaledIm" - "u\022-.mavsdk.rpc.telemetry.SetRateScaledIm" - "uRequest\032..mavsdk.rpc.telemetry.SetRateS" - "caledImuResponse\"\000\022j\n\rSetRateRawImu\022*.ma" - "vsdk.rpc.telemetry.SetRateRawImuRequest\032" - "+.mavsdk.rpc.telemetry.SetRateRawImuResp" - "onse\"\000\022\177\n\024SetRateUnixEpochTime\0221.mavsdk." - "rpc.telemetry.SetRateUnixEpochTimeReques" - "t\0322.mavsdk.rpc.telemetry.SetRateUnixEpoc" - "hTimeResponse\"\000\022\202\001\n\025SetRateDistanceSenso" - "r\0222.mavsdk.rpc.telemetry.SetRateDistance" - "SensorRequest\0323.mavsdk.rpc.telemetry.Set" - "RateDistanceSensorResponse\"\000\022y\n\022GetGpsGl" - "obalOrigin\022/.mavsdk.rpc.telemetry.GetGps" - "GlobalOriginRequest\0320.mavsdk.rpc.telemet" - "ry.GetGpsGlobalOriginResponse\"\000B%\n\023io.ma" - "vsdk.telemetryB\016TelemetryProtob\006proto3" + "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(" + "\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\"" + "\\\n\007Battery\022\021\n\002id\030\003 \001(\rB\005\202\265\030\0010\022\032\n\tvoltage" + "_v\030\001 \001(\002B\007\202\265\030\003NaN\022\"\n\021remaining_percent\030\002" + " \001(\002B\007\202\265\030\003NaN\"\271\002\n\006Health\022.\n\033is_gyrometer" + "_calibration_ok\030\001 \001(\010B\t\202\265\030\005false\0222\n\037is_a" + "ccelerometer_calibration_ok\030\002 \001(\010B\t\202\265\030\005f" + "alse\0221\n\036is_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_o" + "k\030\006 \001(\010B\t\202\265\030\005false\022&\n\023is_home_position_o" + "k\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_o" + "nce\030\001 \001(\010B\t\202\265\030\005false\022\037\n\014is_available\030\002 \001" + "(\010B\t\202\265\030\005false\022(\n\027signal_strength_percent" + "\030\003 \001(\002B\007\202\265\030\003NaN\"N\n\nStatusText\0222\n\004type\030\001 " + "\001(\0162$.mavsdk.rpc.telemetry.StatusTextTyp" + "e\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\024ActuatorOutputStatus\022\025\n\006active\030\001 \001(\r" + "B\005\202\265\030\0010\022\020\n\010actuator\030\002 \003(\002\"\'\n\nCovariance\022" + "\031\n\021covariance_matrix\030\001 \003(\002\";\n\014VelocityBo" + "dy\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\003" + "y_m\030\002 \001(\002\022\013\n\003z_m\030\003 \001(\002\"\354\004\n\010Odometry\022\021\n\tt" + "ime_usec\030\001 \001(\004\0229\n\010frame_id\030\002 \001(\0162\'.mavsd" + "k.rpc.telemetry.Odometry.MavFrame\022\?\n\016chi" + "ld_frame_id\030\003 \001(\0162\'.mavsdk.rpc.telemetry" + ".Odometry.MavFrame\0229\n\rposition_body\030\004 \001(" + "\0132\".mavsdk.rpc.telemetry.PositionBody\022+\n" + "\001q\030\005 \001(\0132 .mavsdk.rpc.telemetry.Quaterni" + "on\0229\n\rvelocity_body\030\006 \001(\0132\".mavsdk.rpc.t" + "elemetry.VelocityBody\022H\n\025angular_velocit" + "y_body\030\007 \001(\0132).mavsdk.rpc.telemetry.Angu" + "larVelocityBody\0229\n\017pose_covariance\030\010 \001(\013" + "2 .mavsdk.rpc.telemetry.Covariance\022=\n\023ve" + "locity_covariance\030\t \001(\0132 .mavsdk.rpc.tel" + "emetry.Covariance\"j\n\010MavFrame\022\023\n\017MAV_FRA" + "ME_UNDEF\020\000\022\026\n\022MAV_FRAME_BODY_NED\020\010\022\030\n\024MA" + "V_FRAME_VISION_NED\020\020\022\027\n\023MAV_FRAME_ESTIM_" + "NED\020\022\"\177\n\016DistanceSensor\022#\n\022minimum_dista" + "nce_m\030\001 \001(\002B\007\202\265\030\003NaN\022#\n\022maximum_distance" + "_m\030\002 \001(\002B\007\202\265\030\003NaN\022#\n\022current_distance_m\030" + "\003 \001(\002B\007\202\265\030\003NaN\"\260\001\n\016ScaledPressure\022\024\n\014tim" + "estamp_us\030\001 \001(\004\022\035\n\025absolute_pressure_hpa" + "\030\002 \001(\002\022!\n\031differential_pressure_hpa\030\003 \001(" + "\002\022\027\n\017temperature_deg\030\004 \001(\002\022-\n%differenti" + "al_pressure_temperature_deg\030\005 \001(\002\"Y\n\013Pos" + "itionNed\022\030\n\007north_m\030\001 \001(\002B\007\202\265\030\003NaN\022\027\n\006ea" + "st_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\023Po" + "sitionVelocityNed\0223\n\010position\030\001 \001(\0132!.ma" + "vsdk.rpc.telemetry.PositionNed\0223\n\010veloci" + "ty\030\002 \001(\0132!.mavsdk.rpc.telemetry.Velocity" + "Ned\"r\n\013GroundTruth\022\035\n\014latitude_deg\030\001 \001(\001" + "B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003Na" + "N\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\003Na" + "N\"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\022AngularV" + "elocityFrd\022\036\n\rforward_rad_s\030\001 \001(\002B\007\202\265\030\003N" + "aN\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\020MagneticFieldFr" + "d\022\036\n\rforward_gauss\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013rig" + "ht_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\003Imu\022\?\n\020acceleration_frd" + "\030\001 \001(\0132%.mavsdk.rpc.telemetry.Accelerati" + "onFrd\022F\n\024angular_velocity_frd\030\002 \001(\0132(.ma" + "vsdk.rpc.telemetry.AngularVelocityFrd\022B\n" + "\022magnetic_field_frd\030\003 \001(\0132&.mavsdk.rpc.t" + "elemetry.MagneticFieldFrd\022!\n\020temperature" + "_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\"\301\001\n\010Al" + "titude\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\023al" + "titude_relative_m\030\004 \001(\002B\007\202\265\030\003NaN\022#\n\022alti" + "tude_terrain_m\030\005 \001(\002B\007\202\265\030\003NaN\"\241\002\n\017Teleme" + "tryResult\022<\n\006result\030\001 \001(\0162,.mavsdk.rpc.t" + "elemetry.TelemetryResult.Result\022\022\n\nresul" + "t_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RESULT_UNKNOWN" + "\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NO_SYST" + "EM\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022\017\n\013RES" + "ULT_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIED\020\005\022\022\n" + "\016RESULT_TIMEOUT\020\006\022\026\n\022RESULT_UNSUPPORTED\020" + "\007*\244\001\n\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n\017FI" + "X_TYPE_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022\023\n\017" + "FIX_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGPS\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_MODE_U" + "NKNOWN\020\000\022\025\n\021FLIGHT_MODE_READY\020\001\022\027\n\023FLIGH" + "T_MODE_TAKEOFF\020\002\022\024\n\020FLIGHT_MODE_HOLD\020\003\022\027" + "\n\023FLIGHT_MODE_MISSION\020\004\022 \n\034FLIGHT_MODE_R" + "ETURN_TO_LAUNCH\020\005\022\024\n\020FLIGHT_MODE_LAND\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\022" + "FLIGHT_MODE_ALTCTL\020\n\022\026\n\022FLIGHT_MODE_POSC" + "TL\020\013\022\024\n\020FLIGHT_MODE_ACRO\020\014\022\032\n\026FLIGHT_MOD" + "E_STABILIZED\020\r\022\031\n\025FLIGHT_MODE_RATTITUDE\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\027S" + "TATUS_TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_TEXT_" + "TYPE_WARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_ERROR" + "\020\004\022\035\n\031STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n\026STA" + "TUS_TEXT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT_TYP" + "E_EMERGENCY\020\007*\223\001\n\013LandedState\022\030\n\024LANDED_" + "STATE_UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_GROUN" + "D\020\001\022\027\n\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LANDED_S" + "TATE_TAKING_OFF\020\003\022\030\n\024LANDED_STATE_LANDIN" + "G\020\004*\215\001\n\tVtolState\022\030\n\024VTOL_STATE_UNDEFINE" + "D\020\000\022\037\n\033VTOL_STATE_TRANSITION_TO_FW\020\001\022\037\n\033" + "VTOL_STATE_TRANSITION_TO_MC\020\002\022\021\n\rVTOL_ST" + "ATE_MC\020\003\022\021\n\rVTOL_STATE_FW\020\0042\2019\n\020Telemetr" + "yService\022o\n\021SubscribePosition\022..mavsdk.r" + "pc.telemetry.SubscribePositionRequest\032&." + "mavsdk.rpc.telemetry.PositionResponse\"\0000" + "\001\022c\n\rSubscribeHome\022*.mavsdk.rpc.telemetr" + "y.SubscribeHomeRequest\032\".mavsdk.rpc.tele" + "metry.HomeResponse\"\0000\001\022f\n\016SubscribeInAir" + "\022+.mavsdk.rpc.telemetry.SubscribeInAirRe" + "quest\032#.mavsdk.rpc.telemetry.InAirRespon" + "se\"\0000\001\022x\n\024SubscribeLandedState\0221.mavsdk." + "rpc.telemetry.SubscribeLandedStateReques" + "t\032).mavsdk.rpc.telemetry.LandedStateResp" + "onse\"\0000\001\022f\n\016SubscribeArmed\022+.mavsdk.rpc." + "telemetry.SubscribeArmedRequest\032#.mavsdk" + ".rpc.telemetry.ArmedResponse\"\0000\001\022r\n\022Subs" + "cribeVtolState\022/.mavsdk.rpc.telemetry.Su" + "bscribeVtolStateRequest\032\'.mavsdk.rpc.tel" + "emetry.VtolStateResponse\"\0000\001\022\215\001\n\033Subscri" + "beAttitudeQuaternion\0228.mavsdk.rpc.teleme" + "try.SubscribeAttitudeQuaternionRequest\0320" + ".mavsdk.rpc.telemetry.AttitudeQuaternion" + "Response\"\0000\001\022~\n\026SubscribeAttitudeEuler\0223" + ".mavsdk.rpc.telemetry.SubscribeAttitudeE" + "ulerRequest\032+.mavsdk.rpc.telemetry.Attit" + "udeEulerResponse\"\0000\001\022\250\001\n$SubscribeAttitu" + "deAngularVelocityBody\022A.mavsdk.rpc.telem" + "etry.SubscribeAttitudeAngularVelocityBod" + "yRequest\0329.mavsdk.rpc.telemetry.Attitude" + "AngularVelocityBodyResponse\"\0000\001\022\237\001\n!Subs" + "cribeCameraAttitudeQuaternion\022>.mavsdk.r" + "pc.telemetry.SubscribeCameraAttitudeQuat" + "ernionRequest\0326.mavsdk.rpc.telemetry.Cam" + "eraAttitudeQuaternionResponse\"\0000\001\022\220\001\n\034Su" + "bscribeCameraAttitudeEuler\0229.mavsdk.rpc." + "telemetry.SubscribeCameraAttitudeEulerRe" + "quest\0321.mavsdk.rpc.telemetry.CameraAttit" + "udeEulerResponse\"\0000\001\022x\n\024SubscribeVelocit" + "yNed\0221.mavsdk.rpc.telemetry.SubscribeVel" + "ocityNedRequest\032).mavsdk.rpc.telemetry.V" + "elocityNedResponse\"\0000\001\022l\n\020SubscribeGpsIn" + "fo\022-.mavsdk.rpc.telemetry.SubscribeGpsIn" + "foRequest\032%.mavsdk.rpc.telemetry.GpsInfo" + "Response\"\0000\001\022i\n\017SubscribeRawGps\022,.mavsdk" + ".rpc.telemetry.SubscribeRawGpsRequest\032$." + "mavsdk.rpc.telemetry.RawGpsResponse\"\0000\001\022" + "l\n\020SubscribeBattery\022-.mavsdk.rpc.telemet" + "ry.SubscribeBatteryRequest\032%.mavsdk.rpc." + "telemetry.BatteryResponse\"\0000\001\022u\n\023Subscri" + "beFlightMode\0220.mavsdk.rpc.telemetry.Subs" + "cribeFlightModeRequest\032(.mavsdk.rpc.tele" + "metry.FlightModeResponse\"\0000\001\022i\n\017Subscrib" + "eHealth\022,.mavsdk.rpc.telemetry.Subscribe" + "HealthRequest\032$.mavsdk.rpc.telemetry.Hea" + "lthResponse\"\0000\001\022o\n\021SubscribeRcStatus\022..m" + "avsdk.rpc.telemetry.SubscribeRcStatusReq" + "uest\032&.mavsdk.rpc.telemetry.RcStatusResp" + "onse\"\0000\001\022u\n\023SubscribeStatusText\0220.mavsdk" + ".rpc.telemetry.SubscribeStatusTextReques" + "t\032(.mavsdk.rpc.telemetry.StatusTextRespo" + "nse\"\0000\001\022\226\001\n\036SubscribeActuatorControlTarg" + "et\022;.mavsdk.rpc.telemetry.SubscribeActua" + "torControlTargetRequest\0323.mavsdk.rpc.tel" + "emetry.ActuatorControlTargetResponse\"\0000\001" + "\022\223\001\n\035SubscribeActuatorOutputStatus\022:.mav" + "sdk.rpc.telemetry.SubscribeActuatorOutpu" + "tStatusRequest\0322.mavsdk.rpc.telemetry.Ac" + "tuatorOutputStatusResponse\"\0000\001\022o\n\021Subscr" + "ibeOdometry\022..mavsdk.rpc.telemetry.Subsc" + "ribeOdometryRequest\032&.mavsdk.rpc.telemet" + "ry.OdometryResponse\"\0000\001\022\220\001\n\034SubscribePos" + "itionVelocityNed\0229.mavsdk.rpc.telemetry." + "SubscribePositionVelocityNedRequest\0321.ma" + "vsdk.rpc.telemetry.PositionVelocityNedRe" + "sponse\"\0000\001\022x\n\024SubscribeGroundTruth\0221.mav" + "sdk.rpc.telemetry.SubscribeGroundTruthRe" + "quest\032).mavsdk.rpc.telemetry.GroundTruth" + "Response\"\0000\001\022\207\001\n\031SubscribeFixedwingMetri" + "cs\0226.mavsdk.rpc.telemetry.SubscribeFixed" + "wingMetricsRequest\032..mavsdk.rpc.telemetr" + "y.FixedwingMetricsResponse\"\0000\001\022`\n\014Subscr" + "ibeImu\022).mavsdk.rpc.telemetry.SubscribeI" + "muRequest\032!.mavsdk.rpc.telemetry.ImuResp" + "onse\"\0000\001\022r\n\022SubscribeScaledImu\022/.mavsdk." + "rpc.telemetry.SubscribeScaledImuRequest\032" + "\'.mavsdk.rpc.telemetry.ScaledImuResponse" + "\"\0000\001\022i\n\017SubscribeRawImu\022,.mavsdk.rpc.tel" + "emetry.SubscribeRawImuRequest\032$.mavsdk.r" + "pc.telemetry.RawImuResponse\"\0000\001\022x\n\024Subsc" + "ribeHealthAllOk\0221.mavsdk.rpc.telemetry.S" + "ubscribeHealthAllOkRequest\032).mavsdk.rpc." + "telemetry.HealthAllOkResponse\"\0000\001\022~\n\026Sub" + "scribeUnixEpochTime\0223.mavsdk.rpc.telemet" + "ry.SubscribeUnixEpochTimeRequest\032+.mavsd" + "k.rpc.telemetry.UnixEpochTimeResponse\"\0000" + "\001\022\201\001\n\027SubscribeDistanceSensor\0224.mavsdk.r" + "pc.telemetry.SubscribeDistanceSensorRequ" + "est\032,.mavsdk.rpc.telemetry.DistanceSenso" + "rResponse\"\0000\001\022\201\001\n\027SubscribeScaledPressur" + "e\0224.mavsdk.rpc.telemetry.SubscribeScaled" + "PressureRequest\032,.mavsdk.rpc.telemetry.S" + "caledPressureResponse\"\0000\001\022l\n\020SubscribeHe" + "ading\022-.mavsdk.rpc.telemetry.SubscribeHe" + "adingRequest\032%.mavsdk.rpc.telemetry.Head" + "ingResponse\"\0000\001\022o\n\021SubscribeAltitude\022..m" + "avsdk.rpc.telemetry.SubscribeAltitudeReq" + "uest\032&.mavsdk.rpc.telemetry.AltitudeResp" + "onse\"\0000\001\022p\n\017SetRatePosition\022,.mavsdk.rpc" + ".telemetry.SetRatePositionRequest\032-.mavs" + "dk.rpc.telemetry.SetRatePositionResponse" + "\"\000\022d\n\013SetRateHome\022(.mavsdk.rpc.telemetry" + ".SetRateHomeRequest\032).mavsdk.rpc.telemet" + "ry.SetRateHomeResponse\"\000\022g\n\014SetRateInAir" + "\022).mavsdk.rpc.telemetry.SetRateInAirRequ" + "est\032*.mavsdk.rpc.telemetry.SetRateInAirR" + "esponse\"\000\022y\n\022SetRateLandedState\022/.mavsdk" + ".rpc.telemetry.SetRateLandedStateRequest" + "\0320.mavsdk.rpc.telemetry.SetRateLandedSta" + "teResponse\"\000\022s\n\020SetRateVtolState\022-.mavsd" + "k.rpc.telemetry.SetRateVtolStateRequest\032" + "..mavsdk.rpc.telemetry.SetRateVtolStateR" + "esponse\"\000\022\216\001\n\031SetRateAttitudeQuaternion\022" + "6.mavsdk.rpc.telemetry.SetRateAttitudeQu" + "aternionRequest\0327.mavsdk.rpc.telemetry.S" + "etRateAttitudeQuaternionResponse\"\000\022\177\n\024Se" + "tRateAttitudeEuler\0221.mavsdk.rpc.telemetr" + "y.SetRateAttitudeEulerRequest\0322.mavsdk.r" + "pc.telemetry.SetRateAttitudeEulerRespons" + "e\"\000\022\202\001\n\025SetRateCameraAttitude\0222.mavsdk.r" + "pc.telemetry.SetRateCameraAttitudeReques" + "t\0323.mavsdk.rpc.telemetry.SetRateCameraAt" + "titudeResponse\"\000\022y\n\022SetRateVelocityNed\022/" + ".mavsdk.rpc.telemetry.SetRateVelocityNed" + "Request\0320.mavsdk.rpc.telemetry.SetRateVe" + "locityNedResponse\"\000\022m\n\016SetRateGpsInfo\022+." + "mavsdk.rpc.telemetry.SetRateGpsInfoReque" + "st\032,.mavsdk.rpc.telemetry.SetRateGpsInfo" + "Response\"\000\022m\n\016SetRateBattery\022+.mavsdk.rp" + "c.telemetry.SetRateBatteryRequest\032,.mavs" + "dk.rpc.telemetry.SetRateBatteryResponse\"" + "\000\022p\n\017SetRateRcStatus\022,.mavsdk.rpc.teleme" + "try.SetRateRcStatusRequest\032-.mavsdk.rpc." + "telemetry.SetRateRcStatusResponse\"\000\022\227\001\n\034" + "SetRateActuatorControlTarget\0229.mavsdk.rp" + "c.telemetry.SetRateActuatorControlTarget" + "Request\032:.mavsdk.rpc.telemetry.SetRateAc" + "tuatorControlTargetResponse\"\000\022\224\001\n\033SetRat" + "eActuatorOutputStatus\0228.mavsdk.rpc.telem" + "etry.SetRateActuatorOutputStatusRequest\032" + "9.mavsdk.rpc.telemetry.SetRateActuatorOu" + "tputStatusResponse\"\000\022p\n\017SetRateOdometry\022" + ",.mavsdk.rpc.telemetry.SetRateOdometryRe" + "quest\032-.mavsdk.rpc.telemetry.SetRateOdom" + "etryResponse\"\000\022\221\001\n\032SetRatePositionVeloci" + "tyNed\0227.mavsdk.rpc.telemetry.SetRatePosi" + "tionVelocityNedRequest\0328.mavsdk.rpc.tele" + "metry.SetRatePositionVelocityNedResponse" + "\"\000\022y\n\022SetRateGroundTruth\022/.mavsdk.rpc.te" + "lemetry.SetRateGroundTruthRequest\0320.mavs" + "dk.rpc.telemetry.SetRateGroundTruthRespo" + "nse\"\000\022\210\001\n\027SetRateFixedwingMetrics\0224.mavs" + "dk.rpc.telemetry.SetRateFixedwingMetrics" + "Request\0325.mavsdk.rpc.telemetry.SetRateFi" + "xedwingMetricsResponse\"\000\022a\n\nSetRateImu\022\'" + ".mavsdk.rpc.telemetry.SetRateImuRequest\032" + "(.mavsdk.rpc.telemetry.SetRateImuRespons" + "e\"\000\022s\n\020SetRateScaledImu\022-.mavsdk.rpc.tel" + "emetry.SetRateScaledImuRequest\032..mavsdk." + "rpc.telemetry.SetRateScaledImuResponse\"\000" + "\022j\n\rSetRateRawImu\022*.mavsdk.rpc.telemetry" + ".SetRateRawImuRequest\032+.mavsdk.rpc.telem" + "etry.SetRateRawImuResponse\"\000\022\177\n\024SetRateU" + "nixEpochTime\0221.mavsdk.rpc.telemetry.SetR" + "ateUnixEpochTimeRequest\0322.mavsdk.rpc.tel" + "emetry.SetRateUnixEpochTimeResponse\"\000\022\202\001" + "\n\025SetRateDistanceSensor\0222.mavsdk.rpc.tel" + "emetry.SetRateDistanceSensorRequest\0323.ma" + "vsdk.rpc.telemetry.SetRateDistanceSensor" + "Response\"\000\022p\n\017SetRateAltitude\022,.mavsdk.r" + "pc.telemetry.SetRateAltitudeRequest\032-.ma" + "vsdk.rpc.telemetry.SetRateAltitudeRespon" + "se\"\000\022y\n\022GetGpsGlobalOrigin\022/.mavsdk.rpc." + "telemetry.GetGpsGlobalOriginRequest\0320.ma" + "vsdk.rpc.telemetry.GetGpsGlobalOriginRes" + "ponse\"\000B%\n\023io.mavsdk.telemetryB\016Telemetr" + "yProtob\006proto3" ; static const ::_pbi::DescriptorTable* const descriptor_table_telemetry_2ftelemetry_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::_pbi::once_flag descriptor_table_telemetry_2ftelemetry_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_telemetry_2ftelemetry_2eproto = { - false, false, 19998, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, + false, false, 20654, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", - &descriptor_table_telemetry_2ftelemetry_2eproto_once, descriptor_table_telemetry_2ftelemetry_2eproto_deps, 1, 149, + &descriptor_table_telemetry_2ftelemetry_2eproto_once, descriptor_table_telemetry_2ftelemetry_2eproto_deps, 1, 154, schemas, file_default_instances, TableStruct_telemetry_2ftelemetry_2eproto::offsets, file_level_metadata_telemetry_2ftelemetry_2eproto, file_level_enum_descriptors_telemetry_2ftelemetry_2eproto, file_level_service_descriptors_telemetry_2ftelemetry_2eproto, @@ -11306,6 +11434,232 @@ ::PROTOBUF_NAMESPACE_ID::Metadata HeadingResponse::GetMetadata() const { // =================================================================== +class SubscribeAltitudeRequest::_Internal { + public: +}; + +SubscribeAltitudeRequest::SubscribeAltitudeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase(arena, is_message_owned) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) +} +SubscribeAltitudeRequest::SubscribeAltitudeRequest(const SubscribeAltitudeRequest& from) + : ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) +} + + + + + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SubscribeAltitudeRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl, + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl, +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SubscribeAltitudeRequest::GetClassData() const { return &_class_data_; } + + + + + + + +::PROTOBUF_NAMESPACE_ID::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: + static const ::mavsdk::rpc::telemetry::Altitude& altitude(const AltitudeResponse* msg); +}; + +const ::mavsdk::rpc::telemetry::Altitude& +AltitudeResponse::_Internal::altitude(const AltitudeResponse* msg) { + return *msg->altitude_; +} +AltitudeResponse::AltitudeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.AltitudeResponse) +} +AltitudeResponse::AltitudeResponse(const AltitudeResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_altitude()) { + altitude_ = new ::mavsdk::rpc::telemetry::Altitude(*from.altitude_); + } else { + altitude_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.AltitudeResponse) +} + +inline void AltitudeResponse::SharedCtor() { +altitude_ = nullptr; +} + +AltitudeResponse::~AltitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.AltitudeResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void AltitudeResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete altitude_; +} + +void AltitudeResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void AltitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.AltitudeResponse) + uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && altitude_ != nullptr) { + delete altitude_; + } + altitude_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* AltitudeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.telemetry.Altitude altitude = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_altitude(), ptr); + CHK_(ptr); + } else + goto handle_unusual; + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +uint8_t* AltitudeResponse::_InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::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; + + // .mavsdk.rpc.telemetry.Altitude altitude = 1; + if (this->_internal_has_altitude()) { + target = ::PROTOBUF_NAMESPACE_ID::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<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::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; + if (this->_internal_has_altitude()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *altitude_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData AltitudeResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + AltitudeResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*AltitudeResponse::GetClassData() const { return &_class_data_; } + +void AltitudeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, + const ::PROTOBUF_NAMESPACE_ID::Message& from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void AltitudeResponse::MergeFrom(const AltitudeResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.AltitudeResponse) + GOOGLE_DCHECK_NE(&from, this); + uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_altitude()) { + _internal_mutable_altitude()->::mavsdk::rpc::telemetry::Altitude::MergeFrom(from._internal_altitude()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::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); +} + +bool AltitudeResponse::IsInitialized() const { + return true; +} + +void AltitudeResponse::InternalSwap(AltitudeResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(altitude_, other->altitude_); +} + +::PROTOBUF_NAMESPACE_ID::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: }; @@ -11484,7 +11838,7 @@ void SetRatePositionRequest::InternalSwap(SetRatePositionRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[66]); + file_level_metadata_telemetry_2ftelemetry_2eproto[68]); } // =================================================================== @@ -11671,7 +12025,7 @@ void SetRatePositionResponse::InternalSwap(SetRatePositionResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[67]); + file_level_metadata_telemetry_2ftelemetry_2eproto[69]); } // =================================================================== @@ -11854,7 +12208,7 @@ void SetRateHomeRequest::InternalSwap(SetRateHomeRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[68]); + file_level_metadata_telemetry_2ftelemetry_2eproto[70]); } // =================================================================== @@ -12041,7 +12395,7 @@ void SetRateHomeResponse::InternalSwap(SetRateHomeResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[69]); + file_level_metadata_telemetry_2ftelemetry_2eproto[71]); } // =================================================================== @@ -12224,7 +12578,7 @@ void SetRateInAirRequest::InternalSwap(SetRateInAirRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[70]); + file_level_metadata_telemetry_2ftelemetry_2eproto[72]); } // =================================================================== @@ -12411,7 +12765,7 @@ void SetRateInAirResponse::InternalSwap(SetRateInAirResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[71]); + file_level_metadata_telemetry_2ftelemetry_2eproto[73]); } // =================================================================== @@ -12594,7 +12948,7 @@ void SetRateLandedStateRequest::InternalSwap(SetRateLandedStateRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[72]); + file_level_metadata_telemetry_2ftelemetry_2eproto[74]); } // =================================================================== @@ -12781,7 +13135,7 @@ void SetRateLandedStateResponse::InternalSwap(SetRateLandedStateResponse* other) ::PROTOBUF_NAMESPACE_ID::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[73]); + file_level_metadata_telemetry_2ftelemetry_2eproto[75]); } // =================================================================== @@ -12964,7 +13318,7 @@ void SetRateVtolStateRequest::InternalSwap(SetRateVtolStateRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[74]); + file_level_metadata_telemetry_2ftelemetry_2eproto[76]); } // =================================================================== @@ -13151,7 +13505,7 @@ void SetRateVtolStateResponse::InternalSwap(SetRateVtolStateResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[75]); + file_level_metadata_telemetry_2ftelemetry_2eproto[77]); } // =================================================================== @@ -13334,7 +13688,7 @@ void SetRateAttitudeEulerRequest::InternalSwap(SetRateAttitudeEulerRequest* othe ::PROTOBUF_NAMESPACE_ID::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[76]); + file_level_metadata_telemetry_2ftelemetry_2eproto[78]); } // =================================================================== @@ -13521,7 +13875,7 @@ void SetRateAttitudeEulerResponse::InternalSwap(SetRateAttitudeEulerResponse* ot ::PROTOBUF_NAMESPACE_ID::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[77]); + file_level_metadata_telemetry_2ftelemetry_2eproto[79]); } // =================================================================== @@ -13704,7 +14058,7 @@ void SetRateAttitudeQuaternionRequest::InternalSwap(SetRateAttitudeQuaternionReq ::PROTOBUF_NAMESPACE_ID::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[78]); + file_level_metadata_telemetry_2ftelemetry_2eproto[80]); } // =================================================================== @@ -13891,7 +14245,7 @@ void SetRateAttitudeQuaternionResponse::InternalSwap(SetRateAttitudeQuaternionRe ::PROTOBUF_NAMESPACE_ID::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[79]); + file_level_metadata_telemetry_2ftelemetry_2eproto[81]); } // =================================================================== @@ -14074,7 +14428,7 @@ void SetRateAttitudeAngularVelocityBodyRequest::InternalSwap(SetRateAttitudeAngu ::PROTOBUF_NAMESPACE_ID::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[80]); + file_level_metadata_telemetry_2ftelemetry_2eproto[82]); } // =================================================================== @@ -14261,7 +14615,7 @@ void SetRateAttitudeAngularVelocityBodyResponse::InternalSwap(SetRateAttitudeAng ::PROTOBUF_NAMESPACE_ID::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[81]); + file_level_metadata_telemetry_2ftelemetry_2eproto[83]); } // =================================================================== @@ -14444,7 +14798,7 @@ void SetRateCameraAttitudeQuaternionRequest::InternalSwap(SetRateCameraAttitudeQ ::PROTOBUF_NAMESPACE_ID::Metadata SetRateCameraAttitudeQuaternionRequest::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[84]); } // =================================================================== @@ -14631,7 +14985,7 @@ void SetRateCameraAttitudeQuaternionResponse::InternalSwap(SetRateCameraAttitude ::PROTOBUF_NAMESPACE_ID::Metadata SetRateCameraAttitudeQuaternionResponse::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[85]); } // =================================================================== @@ -14814,7 +15168,7 @@ void SetRateCameraAttitudeRequest::InternalSwap(SetRateCameraAttitudeRequest* ot ::PROTOBUF_NAMESPACE_ID::Metadata SetRateCameraAttitudeRequest::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[86]); } // =================================================================== @@ -15001,7 +15355,7 @@ void SetRateCameraAttitudeResponse::InternalSwap(SetRateCameraAttitudeResponse* ::PROTOBUF_NAMESPACE_ID::Metadata SetRateCameraAttitudeResponse::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[87]); } // =================================================================== @@ -15184,7 +15538,7 @@ void SetRateVelocityNedRequest::InternalSwap(SetRateVelocityNedRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[86]); + file_level_metadata_telemetry_2ftelemetry_2eproto[88]); } // =================================================================== @@ -15371,7 +15725,7 @@ void SetRateVelocityNedResponse::InternalSwap(SetRateVelocityNedResponse* other) ::PROTOBUF_NAMESPACE_ID::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[87]); + file_level_metadata_telemetry_2ftelemetry_2eproto[89]); } // =================================================================== @@ -15554,7 +15908,7 @@ void SetRateGpsInfoRequest::InternalSwap(SetRateGpsInfoRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[88]); + file_level_metadata_telemetry_2ftelemetry_2eproto[90]); } // =================================================================== @@ -15741,7 +16095,7 @@ void SetRateGpsInfoResponse::InternalSwap(SetRateGpsInfoResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[89]); + file_level_metadata_telemetry_2ftelemetry_2eproto[91]); } // =================================================================== @@ -15924,7 +16278,7 @@ void SetRateRawGpsRequest::InternalSwap(SetRateRawGpsRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[90]); + file_level_metadata_telemetry_2ftelemetry_2eproto[92]); } // =================================================================== @@ -16107,7 +16461,7 @@ void SetRateBatteryRequest::InternalSwap(SetRateBatteryRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[91]); + file_level_metadata_telemetry_2ftelemetry_2eproto[93]); } // =================================================================== @@ -16294,7 +16648,7 @@ void SetRateBatteryResponse::InternalSwap(SetRateBatteryResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[92]); + file_level_metadata_telemetry_2ftelemetry_2eproto[94]); } // =================================================================== @@ -16477,7 +16831,7 @@ void SetRateRcStatusRequest::InternalSwap(SetRateRcStatusRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[93]); + file_level_metadata_telemetry_2ftelemetry_2eproto[95]); } // =================================================================== @@ -16664,7 +17018,7 @@ void SetRateRcStatusResponse::InternalSwap(SetRateRcStatusResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[94]); + file_level_metadata_telemetry_2ftelemetry_2eproto[96]); } // =================================================================== @@ -16847,7 +17201,7 @@ void SetRateActuatorControlTargetRequest::InternalSwap(SetRateActuatorControlTar ::PROTOBUF_NAMESPACE_ID::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[95]); + file_level_metadata_telemetry_2ftelemetry_2eproto[97]); } // =================================================================== @@ -17034,7 +17388,7 @@ void SetRateActuatorControlTargetResponse::InternalSwap(SetRateActuatorControlTa ::PROTOBUF_NAMESPACE_ID::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[96]); + file_level_metadata_telemetry_2ftelemetry_2eproto[98]); } // =================================================================== @@ -17217,7 +17571,7 @@ void SetRateActuatorOutputStatusRequest::InternalSwap(SetRateActuatorOutputStatu ::PROTOBUF_NAMESPACE_ID::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[97]); + file_level_metadata_telemetry_2ftelemetry_2eproto[99]); } // =================================================================== @@ -17404,7 +17758,7 @@ void SetRateActuatorOutputStatusResponse::InternalSwap(SetRateActuatorOutputStat ::PROTOBUF_NAMESPACE_ID::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[98]); + file_level_metadata_telemetry_2ftelemetry_2eproto[100]); } // =================================================================== @@ -17587,7 +17941,7 @@ void SetRateOdometryRequest::InternalSwap(SetRateOdometryRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[99]); + file_level_metadata_telemetry_2ftelemetry_2eproto[101]); } // =================================================================== @@ -17774,7 +18128,7 @@ void SetRateOdometryResponse::InternalSwap(SetRateOdometryResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[100]); + file_level_metadata_telemetry_2ftelemetry_2eproto[102]); } // =================================================================== @@ -17957,7 +18311,7 @@ void SetRatePositionVelocityNedRequest::InternalSwap(SetRatePositionVelocityNedR ::PROTOBUF_NAMESPACE_ID::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[101]); + file_level_metadata_telemetry_2ftelemetry_2eproto[103]); } // =================================================================== @@ -18144,7 +18498,7 @@ void SetRatePositionVelocityNedResponse::InternalSwap(SetRatePositionVelocityNed ::PROTOBUF_NAMESPACE_ID::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[102]); + file_level_metadata_telemetry_2ftelemetry_2eproto[104]); } // =================================================================== @@ -18327,7 +18681,7 @@ void SetRateGroundTruthRequest::InternalSwap(SetRateGroundTruthRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[103]); + file_level_metadata_telemetry_2ftelemetry_2eproto[105]); } // =================================================================== @@ -18514,7 +18868,7 @@ void SetRateGroundTruthResponse::InternalSwap(SetRateGroundTruthResponse* other) ::PROTOBUF_NAMESPACE_ID::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[104]); + file_level_metadata_telemetry_2ftelemetry_2eproto[106]); } // =================================================================== @@ -18697,7 +19051,7 @@ void SetRateFixedwingMetricsRequest::InternalSwap(SetRateFixedwingMetricsRequest ::PROTOBUF_NAMESPACE_ID::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[105]); + file_level_metadata_telemetry_2ftelemetry_2eproto[107]); } // =================================================================== @@ -18884,7 +19238,7 @@ void SetRateFixedwingMetricsResponse::InternalSwap(SetRateFixedwingMetricsRespon ::PROTOBUF_NAMESPACE_ID::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[106]); + file_level_metadata_telemetry_2ftelemetry_2eproto[108]); } // =================================================================== @@ -19067,7 +19421,7 @@ void SetRateImuRequest::InternalSwap(SetRateImuRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[107]); + file_level_metadata_telemetry_2ftelemetry_2eproto[109]); } // =================================================================== @@ -19254,7 +19608,7 @@ void SetRateImuResponse::InternalSwap(SetRateImuResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[108]); + file_level_metadata_telemetry_2ftelemetry_2eproto[110]); } // =================================================================== @@ -19437,7 +19791,7 @@ void SetRateScaledImuRequest::InternalSwap(SetRateScaledImuRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[109]); + file_level_metadata_telemetry_2ftelemetry_2eproto[111]); } // =================================================================== @@ -19624,7 +19978,7 @@ void SetRateScaledImuResponse::InternalSwap(SetRateScaledImuResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[110]); + file_level_metadata_telemetry_2ftelemetry_2eproto[112]); } // =================================================================== @@ -19807,7 +20161,7 @@ void SetRateRawImuRequest::InternalSwap(SetRateRawImuRequest* other) { ::PROTOBUF_NAMESPACE_ID::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[111]); + file_level_metadata_telemetry_2ftelemetry_2eproto[113]); } // =================================================================== @@ -19994,7 +20348,7 @@ void SetRateRawImuResponse::InternalSwap(SetRateRawImuResponse* other) { ::PROTOBUF_NAMESPACE_ID::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[112]); + file_level_metadata_telemetry_2ftelemetry_2eproto[114]); } // =================================================================== @@ -20177,7 +20531,7 @@ void SetRateUnixEpochTimeRequest::InternalSwap(SetRateUnixEpochTimeRequest* othe ::PROTOBUF_NAMESPACE_ID::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[113]); + file_level_metadata_telemetry_2ftelemetry_2eproto[115]); } // =================================================================== @@ -20364,7 +20718,7 @@ void SetRateUnixEpochTimeResponse::InternalSwap(SetRateUnixEpochTimeResponse* ot ::PROTOBUF_NAMESPACE_ID::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[114]); + file_level_metadata_telemetry_2ftelemetry_2eproto[116]); } // =================================================================== @@ -20547,7 +20901,7 @@ void SetRateDistanceSensorRequest::InternalSwap(SetRateDistanceSensorRequest* ot ::PROTOBUF_NAMESPACE_ID::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[115]); + file_level_metadata_telemetry_2ftelemetry_2eproto[117]); } // =================================================================== @@ -20734,7 +21088,7 @@ void SetRateDistanceSensorResponse::InternalSwap(SetRateDistanceSensorResponse* ::PROTOBUF_NAMESPACE_ID::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[116]); + file_level_metadata_telemetry_2ftelemetry_2eproto[118]); } // =================================================================== @@ -20773,7 +21127,7 @@ const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetGpsGlobalOriginRequest::Get ::PROTOBUF_NAMESPACE_ID::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[117]); + file_level_metadata_telemetry_2ftelemetry_2eproto[119]); } // =================================================================== @@ -21008,7 +21362,377 @@ void GetGpsGlobalOriginResponse::InternalSwap(GetGpsGlobalOriginResponse* other) ::PROTOBUF_NAMESPACE_ID::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[118]); + file_level_metadata_telemetry_2ftelemetry_2eproto[120]); +} + +// =================================================================== + +class SetRateAltitudeRequest::_Internal { + public: +}; + +SetRateAltitudeRequest::SetRateAltitudeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAltitudeRequest) +} +SetRateAltitudeRequest::SetRateAltitudeRequest(const SetRateAltitudeRequest& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + rate_hz_ = from.rate_hz_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAltitudeRequest) +} + +inline void SetRateAltitudeRequest::SharedCtor() { +rate_hz_ = 0; +} + +SetRateAltitudeRequest::~SetRateAltitudeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetRateAltitudeRequest::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void SetRateAltitudeRequest::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetRateAltitudeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + rate_hz_ = 0; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetRateAltitudeRequest::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // double rate_hz = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 9)) { + rate_hz_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(double); + } else + goto handle_unusual; + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +uint8_t* SetRateAltitudeRequest::_InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + 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<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + return target; +} + +size_t SetRateAltitudeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + 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 += 1 + 8; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRateAltitudeRequest::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetRateAltitudeRequest::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRateAltitudeRequest::GetClassData() const { return &_class_data_; } + +void SetRateAltitudeRequest::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, + const ::PROTOBUF_NAMESPACE_ID::Message& from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetRateAltitudeRequest::MergeFrom(const SetRateAltitudeRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + GOOGLE_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) { + _internal_set_rate_hz(from._internal_rate_hz()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetRateAltitudeRequest::CopyFrom(const SetRateAltitudeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAltitudeRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetRateAltitudeRequest::IsInitialized() const { + return true; +} + +void SetRateAltitudeRequest::InternalSwap(SetRateAltitudeRequest* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(rate_hz_, other->rate_hz_); +} + +::PROTOBUF_NAMESPACE_ID::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]); +} + +// =================================================================== + +class SetRateAltitudeResponse::_Internal { + public: + static const ::mavsdk::rpc::telemetry::TelemetryResult& telemetry_result(const SetRateAltitudeResponse* msg); +}; + +const ::mavsdk::rpc::telemetry::TelemetryResult& +SetRateAltitudeResponse::_Internal::telemetry_result(const SetRateAltitudeResponse* msg) { + return *msg->telemetry_result_; +} +SetRateAltitudeResponse::SetRateAltitudeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.SetRateAltitudeResponse) +} +SetRateAltitudeResponse::SetRateAltitudeResponse(const SetRateAltitudeResponse& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_telemetry_result()) { + telemetry_result_ = new ::mavsdk::rpc::telemetry::TelemetryResult(*from.telemetry_result_); + } else { + telemetry_result_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SetRateAltitudeResponse) +} + +inline void SetRateAltitudeResponse::SharedCtor() { +telemetry_result_ = nullptr; +} + +SetRateAltitudeResponse::~SetRateAltitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void SetRateAltitudeResponse::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete telemetry_result_; +} + +void SetRateAltitudeResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void SetRateAltitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaForAllocation() == nullptr && telemetry_result_ != nullptr) { + delete telemetry_result_; + } + telemetry_result_ = nullptr; + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* SetRateAltitudeResponse::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 10)) { + ptr = ctx->ParseMessage(_internal_mutable_telemetry_result(), ptr); + CHK_(ptr); + } else + goto handle_unusual; + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +uint8_t* SetRateAltitudeResponse::_InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + if (this->_internal_has_telemetry_result()) { + target = ::PROTOBUF_NAMESPACE_ID::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<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + return target; +} + +size_t SetRateAltitudeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + 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; + if (this->_internal_has_telemetry_result()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *telemetry_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData SetRateAltitudeResponse::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + SetRateAltitudeResponse::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*SetRateAltitudeResponse::GetClassData() const { return &_class_data_; } + +void SetRateAltitudeResponse::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, + const ::PROTOBUF_NAMESPACE_ID::Message& from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void SetRateAltitudeResponse::MergeFrom(const SetRateAltitudeResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + GOOGLE_DCHECK_NE(&from, this); + uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_has_telemetry_result()) { + _internal_mutable_telemetry_result()->::mavsdk::rpc::telemetry::TelemetryResult::MergeFrom(from._internal_telemetry_result()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void SetRateAltitudeResponse::CopyFrom(const SetRateAltitudeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SetRateAltitudeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SetRateAltitudeResponse::IsInitialized() const { + return true; +} + +void SetRateAltitudeResponse::InternalSwap(SetRateAltitudeResponse* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(telemetry_result_, other->telemetry_result_); +} + +::PROTOBUF_NAMESPACE_ID::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]); } // =================================================================== @@ -21305,7 +22029,7 @@ void Position::InternalSwap(Position* other) { ::PROTOBUF_NAMESPACE_ID::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[119]); + file_level_metadata_telemetry_2ftelemetry_2eproto[123]); } // =================================================================== @@ -21488,7 +22212,7 @@ void Heading::InternalSwap(Heading* other) { ::PROTOBUF_NAMESPACE_ID::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[120]); + file_level_metadata_telemetry_2ftelemetry_2eproto[124]); } // =================================================================== @@ -21807,7 +22531,7 @@ void Quaternion::InternalSwap(Quaternion* other) { ::PROTOBUF_NAMESPACE_ID::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[121]); + file_level_metadata_telemetry_2ftelemetry_2eproto[125]); } // =================================================================== @@ -22092,7 +22816,7 @@ void EulerAngle::InternalSwap(EulerAngle* other) { ::PROTOBUF_NAMESPACE_ID::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[122]); + file_level_metadata_telemetry_2ftelemetry_2eproto[126]); } // =================================================================== @@ -22355,7 +23079,7 @@ void AngularVelocityBody::InternalSwap(AngularVelocityBody* other) { ::PROTOBUF_NAMESPACE_ID::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[123]); + file_level_metadata_telemetry_2ftelemetry_2eproto[127]); } // =================================================================== @@ -22563,7 +23287,7 @@ void GpsInfo::InternalSwap(GpsInfo* other) { ::PROTOBUF_NAMESPACE_ID::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[124]); + file_level_metadata_telemetry_2ftelemetry_2eproto[128]); } // =================================================================== @@ -23188,7 +23912,7 @@ void RawGps::InternalSwap(RawGps* other) { ::PROTOBUF_NAMESPACE_ID::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[125]); + file_level_metadata_telemetry_2ftelemetry_2eproto[129]); } // =================================================================== @@ -23439,7 +24163,7 @@ void Battery::InternalSwap(Battery* other) { ::PROTOBUF_NAMESPACE_ID::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[126]); + file_level_metadata_telemetry_2ftelemetry_2eproto[130]); } // =================================================================== @@ -23754,7 +24478,7 @@ void Health::InternalSwap(Health* other) { ::PROTOBUF_NAMESPACE_ID::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[127]); + file_level_metadata_telemetry_2ftelemetry_2eproto[131]); } // =================================================================== @@ -23993,7 +24717,7 @@ void RcStatus::InternalSwap(RcStatus* other) { ::PROTOBUF_NAMESPACE_ID::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[128]); + file_level_metadata_telemetry_2ftelemetry_2eproto[132]); } // =================================================================== @@ -24217,7 +24941,7 @@ void StatusText::InternalSwap(StatusText* other) { ::PROTOBUF_NAMESPACE_ID::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[129]); + file_level_metadata_telemetry_2ftelemetry_2eproto[133]); } // =================================================================== @@ -24420,7 +25144,7 @@ void ActuatorControlTarget::InternalSwap(ActuatorControlTarget* other) { ::PROTOBUF_NAMESPACE_ID::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[130]); + file_level_metadata_telemetry_2ftelemetry_2eproto[134]); } // =================================================================== @@ -24623,7 +25347,7 @@ void ActuatorOutputStatus::InternalSwap(ActuatorOutputStatus* other) { ::PROTOBUF_NAMESPACE_ID::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[131]); + file_level_metadata_telemetry_2ftelemetry_2eproto[135]); } // =================================================================== @@ -24800,7 +25524,7 @@ void Covariance::InternalSwap(Covariance* other) { ::PROTOBUF_NAMESPACE_ID::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[132]); + file_level_metadata_telemetry_2ftelemetry_2eproto[136]); } // =================================================================== @@ -25063,7 +25787,7 @@ void VelocityBody::InternalSwap(VelocityBody* other) { ::PROTOBUF_NAMESPACE_ID::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[133]); + file_level_metadata_telemetry_2ftelemetry_2eproto[137]); } // =================================================================== @@ -25326,7 +26050,7 @@ void PositionBody::InternalSwap(PositionBody* other) { ::PROTOBUF_NAMESPACE_ID::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[134]); + file_level_metadata_telemetry_2ftelemetry_2eproto[138]); } // =================================================================== @@ -25799,7 +26523,7 @@ void Odometry::InternalSwap(Odometry* other) { ::PROTOBUF_NAMESPACE_ID::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[135]); + file_level_metadata_telemetry_2ftelemetry_2eproto[139]); } // =================================================================== @@ -26062,7 +26786,7 @@ void DistanceSensor::InternalSwap(DistanceSensor* other) { ::PROTOBUF_NAMESPACE_ID::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[136]); + file_level_metadata_telemetry_2ftelemetry_2eproto[140]); } // =================================================================== @@ -26381,7 +27105,7 @@ void ScaledPressure::InternalSwap(ScaledPressure* other) { ::PROTOBUF_NAMESPACE_ID::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[137]); + file_level_metadata_telemetry_2ftelemetry_2eproto[141]); } // =================================================================== @@ -26644,7 +27368,7 @@ void PositionNed::InternalSwap(PositionNed* other) { ::PROTOBUF_NAMESPACE_ID::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[138]); + file_level_metadata_telemetry_2ftelemetry_2eproto[142]); } // =================================================================== @@ -26907,7 +27631,7 @@ void VelocityNed::InternalSwap(VelocityNed* other) { ::PROTOBUF_NAMESPACE_ID::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[139]); + file_level_metadata_telemetry_2ftelemetry_2eproto[143]); } // =================================================================== @@ -27142,7 +27866,7 @@ void PositionVelocityNed::InternalSwap(PositionVelocityNed* other) { ::PROTOBUF_NAMESPACE_ID::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[140]); + file_level_metadata_telemetry_2ftelemetry_2eproto[144]); } // =================================================================== @@ -27405,7 +28129,7 @@ void GroundTruth::InternalSwap(GroundTruth* other) { ::PROTOBUF_NAMESPACE_ID::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[141]); + file_level_metadata_telemetry_2ftelemetry_2eproto[145]); } // =================================================================== @@ -27668,7 +28392,7 @@ void FixedwingMetrics::InternalSwap(FixedwingMetrics* other) { ::PROTOBUF_NAMESPACE_ID::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[142]); + file_level_metadata_telemetry_2ftelemetry_2eproto[146]); } // =================================================================== @@ -27931,7 +28655,7 @@ void AccelerationFrd::InternalSwap(AccelerationFrd* other) { ::PROTOBUF_NAMESPACE_ID::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[143]); + file_level_metadata_telemetry_2ftelemetry_2eproto[147]); } // =================================================================== @@ -28194,7 +28918,7 @@ void AngularVelocityFrd::InternalSwap(AngularVelocityFrd* other) { ::PROTOBUF_NAMESPACE_ID::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[144]); + file_level_metadata_telemetry_2ftelemetry_2eproto[148]); } // =================================================================== @@ -28457,7 +29181,7 @@ void MagneticFieldFrd::InternalSwap(MagneticFieldFrd* other) { ::PROTOBUF_NAMESPACE_ID::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[145]); + file_level_metadata_telemetry_2ftelemetry_2eproto[149]); } // =================================================================== @@ -28794,7 +29518,7 @@ void Imu::InternalSwap(Imu* other) { ::PROTOBUF_NAMESPACE_ID::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[146]); + file_level_metadata_telemetry_2ftelemetry_2eproto[150]); } // =================================================================== @@ -29057,7 +29781,338 @@ void GpsGlobalOrigin::InternalSwap(GpsGlobalOrigin* other) { ::PROTOBUF_NAMESPACE_ID::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[147]); + file_level_metadata_telemetry_2ftelemetry_2eproto[151]); +} + +// =================================================================== + +class Altitude::_Internal { + public: +}; + +Altitude::Altitude(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned) + : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned) { + SharedCtor(); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry.Altitude) +} +Altitude::Altitude(const Altitude& from) + : ::PROTOBUF_NAMESPACE_ID::Message() { + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + ::memcpy(&altitude_monotonic_m_, &from.altitude_monotonic_m_, + static_cast(reinterpret_cast(&altitude_terrain_m_) - + reinterpret_cast(&altitude_monotonic_m_)) + sizeof(altitude_terrain_m_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Altitude) +} + +inline void Altitude::SharedCtor() { +::memset(reinterpret_cast(this) + static_cast( + reinterpret_cast(&altitude_monotonic_m_) - reinterpret_cast(this)), + 0, static_cast(reinterpret_cast(&altitude_terrain_m_) - + reinterpret_cast(&altitude_monotonic_m_)) + sizeof(altitude_terrain_m_)); +} + +Altitude::~Altitude() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Altitude) + if (auto *arena = _internal_metadata_.DeleteReturnArena<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>()) { + (void)arena; + return; + } + SharedDtor(); +} + +inline void Altitude::SharedDtor() { + GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); +} + +void Altitude::SetCachedSize(int size) const { + _cached_size_.Set(size); +} + +void Altitude::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Altitude) + uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&altitude_monotonic_m_, 0, static_cast( + reinterpret_cast(&altitude_terrain_m_) - + reinterpret_cast(&altitude_monotonic_m_)) + sizeof(altitude_terrain_m_)); + _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); +} + +const char* Altitude::_InternalParse(const char* ptr, ::_pbi::ParseContext* ctx) { +#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure + while (!ctx->Done(&ptr)) { + uint32_t tag; + ptr = ::_pbi::ReadTag(ptr, &tag); + switch (tag >> 3) { + // float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + case 1: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 13)) { + altitude_monotonic_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else + goto handle_unusual; + continue; + // float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + case 2: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 21)) { + altitude_amsl_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else + goto handle_unusual; + continue; + // float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + case 3: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 29)) { + altitude_local_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else + goto handle_unusual; + continue; + // float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 37)) { + altitude_relative_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else + goto handle_unusual; + continue; + // float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; + case 5: + if (PROTOBUF_PREDICT_TRUE(static_cast(tag) == 45)) { + altitude_terrain_m_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); + } else + goto handle_unusual; + continue; + default: + goto handle_unusual; + } // switch + handle_unusual: + if ((tag == 0) || ((tag & 7) == 4)) { + CHK_(ptr); + ctx->SetLastTag(tag); + goto message_done; + } + ptr = UnknownFieldParse( + tag, + _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(), + ptr, ctx); + CHK_(ptr != nullptr); + } // while +message_done: + return ptr; +failure: + ptr = nullptr; + goto message_done; +#undef CHK_ +} + +uint8_t* Altitude::_InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Altitude) + uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + // float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_monotonic_m = this->_internal_altitude_monotonic_m(); + uint32_t raw_altitude_monotonic_m; + memcpy(&raw_altitude_monotonic_m, &tmp_altitude_monotonic_m, sizeof(tmp_altitude_monotonic_m)); + if (raw_altitude_monotonic_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray(1, this->_internal_altitude_monotonic_m(), target); + } + + // float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_amsl_m = this->_internal_altitude_amsl_m(); + uint32_t raw_altitude_amsl_m; + memcpy(&raw_altitude_amsl_m, &tmp_altitude_amsl_m, sizeof(tmp_altitude_amsl_m)); + if (raw_altitude_amsl_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray(2, this->_internal_altitude_amsl_m(), target); + } + + // float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_local_m = this->_internal_altitude_local_m(); + uint32_t raw_altitude_local_m; + memcpy(&raw_altitude_local_m, &tmp_altitude_local_m, sizeof(tmp_altitude_local_m)); + if (raw_altitude_local_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray(3, this->_internal_altitude_local_m(), target); + } + + // float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_relative_m = this->_internal_altitude_relative_m(); + uint32_t raw_altitude_relative_m; + memcpy(&raw_altitude_relative_m, &tmp_altitude_relative_m, sizeof(tmp_altitude_relative_m)); + if (raw_altitude_relative_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray(4, this->_internal_altitude_relative_m(), target); + } + + // float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_terrain_m = this->_internal_altitude_terrain_m(); + uint32_t raw_altitude_terrain_m; + memcpy(&raw_altitude_terrain_m, &tmp_altitude_terrain_m, sizeof(tmp_altitude_terrain_m)); + if (raw_altitude_terrain_m != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray(5, this->_internal_altitude_terrain_m(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Altitude) + return target; +} + +size_t Altitude::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Altitude) + size_t total_size = 0; + + uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_monotonic_m = this->_internal_altitude_monotonic_m(); + uint32_t raw_altitude_monotonic_m; + memcpy(&raw_altitude_monotonic_m, &tmp_altitude_monotonic_m, sizeof(tmp_altitude_monotonic_m)); + if (raw_altitude_monotonic_m != 0) { + total_size += 1 + 4; + } + + // float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_amsl_m = this->_internal_altitude_amsl_m(); + uint32_t raw_altitude_amsl_m; + memcpy(&raw_altitude_amsl_m, &tmp_altitude_amsl_m, sizeof(tmp_altitude_amsl_m)); + if (raw_altitude_amsl_m != 0) { + total_size += 1 + 4; + } + + // float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_local_m = this->_internal_altitude_local_m(); + uint32_t raw_altitude_local_m; + memcpy(&raw_altitude_local_m, &tmp_altitude_local_m, sizeof(tmp_altitude_local_m)); + if (raw_altitude_local_m != 0) { + total_size += 1 + 4; + } + + // float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_relative_m = this->_internal_altitude_relative_m(); + uint32_t raw_altitude_relative_m; + memcpy(&raw_altitude_relative_m, &tmp_altitude_relative_m, sizeof(tmp_altitude_relative_m)); + if (raw_altitude_relative_m != 0) { + total_size += 1 + 4; + } + + // float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_terrain_m = this->_internal_altitude_terrain_m(); + uint32_t raw_altitude_terrain_m; + memcpy(&raw_altitude_terrain_m, &tmp_altitude_terrain_m, sizeof(tmp_altitude_terrain_m)); + if (raw_altitude_terrain_m != 0) { + total_size += 1 + 4; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_cached_size_); +} + +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData Altitude::_class_data_ = { + ::PROTOBUF_NAMESPACE_ID::Message::CopyWithSizeCheck, + Altitude::MergeImpl +}; +const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*Altitude::GetClassData() const { return &_class_data_; } + +void Altitude::MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, + const ::PROTOBUF_NAMESPACE_ID::Message& from) { + static_cast(to)->MergeFrom( + static_cast(from)); +} + + +void Altitude::MergeFrom(const Altitude& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Altitude) + GOOGLE_DCHECK_NE(&from, this); + uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_monotonic_m = from._internal_altitude_monotonic_m(); + uint32_t raw_altitude_monotonic_m; + memcpy(&raw_altitude_monotonic_m, &tmp_altitude_monotonic_m, sizeof(tmp_altitude_monotonic_m)); + if (raw_altitude_monotonic_m != 0) { + _internal_set_altitude_monotonic_m(from._internal_altitude_monotonic_m()); + } + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_amsl_m = from._internal_altitude_amsl_m(); + uint32_t raw_altitude_amsl_m; + memcpy(&raw_altitude_amsl_m, &tmp_altitude_amsl_m, sizeof(tmp_altitude_amsl_m)); + if (raw_altitude_amsl_m != 0) { + _internal_set_altitude_amsl_m(from._internal_altitude_amsl_m()); + } + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_local_m = from._internal_altitude_local_m(); + uint32_t raw_altitude_local_m; + memcpy(&raw_altitude_local_m, &tmp_altitude_local_m, sizeof(tmp_altitude_local_m)); + if (raw_altitude_local_m != 0) { + _internal_set_altitude_local_m(from._internal_altitude_local_m()); + } + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_relative_m = from._internal_altitude_relative_m(); + uint32_t raw_altitude_relative_m; + memcpy(&raw_altitude_relative_m, &tmp_altitude_relative_m, sizeof(tmp_altitude_relative_m)); + if (raw_altitude_relative_m != 0) { + _internal_set_altitude_relative_m(from._internal_altitude_relative_m()); + } + static_assert(sizeof(uint32_t) == sizeof(float), "Code assumes uint32_t and float are the same size."); + float tmp_altitude_terrain_m = from._internal_altitude_terrain_m(); + uint32_t raw_altitude_terrain_m; + memcpy(&raw_altitude_terrain_m, &tmp_altitude_terrain_m, sizeof(tmp_altitude_terrain_m)); + if (raw_altitude_terrain_m != 0) { + _internal_set_altitude_terrain_m(from._internal_altitude_terrain_m()); + } + _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); +} + +void Altitude::CopyFrom(const Altitude& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Altitude) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Altitude::IsInitialized() const { + return true; +} + +void Altitude::InternalSwap(Altitude* other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::PROTOBUF_NAMESPACE_ID::internal::memswap< + PROTOBUF_FIELD_OFFSET(Altitude, altitude_terrain_m_) + + sizeof(Altitude::altitude_terrain_m_) + - PROTOBUF_FIELD_OFFSET(Altitude, altitude_monotonic_m_)>( + reinterpret_cast(&altitude_monotonic_m_), + reinterpret_cast(&other->altitude_monotonic_m_)); +} + +::PROTOBUF_NAMESPACE_ID::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]); } // =================================================================== @@ -29281,7 +30336,7 @@ void TelemetryResult::InternalSwap(TelemetryResult* other) { ::PROTOBUF_NAMESPACE_ID::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[148]); + file_level_metadata_telemetry_2ftelemetry_2eproto[153]); } // @@protoc_insertion_point(namespace_scope) @@ -29553,6 +30608,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::HeadingResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::HeadingResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::HeadingResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::AltitudeResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::AltitudeResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::AltitudeResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SetRatePositionRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SetRatePositionRequest >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::SetRatePositionRequest >(arena); @@ -29765,6 +30828,14 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::GetGpsGlobalOriginRespons Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::GetGpsGlobalOriginResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* +Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::SetRateAltitudeRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* +Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::SetRateAltitudeResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::Position* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::Position >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::Position >(arena); @@ -29881,6 +30952,10 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::GpsGlobalOrigin* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::GpsGlobalOrigin >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::GpsGlobalOrigin >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::Altitude* +Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::Altitude >(Arena* arena) { + return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::Altitude >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::TelemetryResult* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::TelemetryResult >(Arena* arena) { return Arena::CreateMessageInternal< ::mavsdk::rpc::telemetry::TelemetryResult >(arena); diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h index 436e0bb419..75117b1553 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h @@ -65,6 +65,12 @@ extern ActuatorOutputStatusDefaultTypeInternal _ActuatorOutputStatus_default_ins class ActuatorOutputStatusResponse; struct ActuatorOutputStatusResponseDefaultTypeInternal; extern ActuatorOutputStatusResponseDefaultTypeInternal _ActuatorOutputStatusResponse_default_instance_; +class Altitude; +struct AltitudeDefaultTypeInternal; +extern AltitudeDefaultTypeInternal _Altitude_default_instance_; +class AltitudeResponse; +struct AltitudeResponseDefaultTypeInternal; +extern AltitudeResponseDefaultTypeInternal _AltitudeResponse_default_instance_; class AngularVelocityBody; struct AngularVelocityBodyDefaultTypeInternal; extern AngularVelocityBodyDefaultTypeInternal _AngularVelocityBody_default_instance_; @@ -233,6 +239,12 @@ extern SetRateActuatorOutputStatusRequestDefaultTypeInternal _SetRateActuatorOut class SetRateActuatorOutputStatusResponse; struct SetRateActuatorOutputStatusResponseDefaultTypeInternal; extern SetRateActuatorOutputStatusResponseDefaultTypeInternal _SetRateActuatorOutputStatusResponse_default_instance_; +class SetRateAltitudeRequest; +struct SetRateAltitudeRequestDefaultTypeInternal; +extern SetRateAltitudeRequestDefaultTypeInternal _SetRateAltitudeRequest_default_instance_; +class SetRateAltitudeResponse; +struct SetRateAltitudeResponseDefaultTypeInternal; +extern SetRateAltitudeResponseDefaultTypeInternal _SetRateAltitudeResponse_default_instance_; class SetRateAttitudeAngularVelocityBodyRequest; struct SetRateAttitudeAngularVelocityBodyRequestDefaultTypeInternal; extern SetRateAttitudeAngularVelocityBodyRequestDefaultTypeInternal _SetRateAttitudeAngularVelocityBodyRequest_default_instance_; @@ -386,6 +398,9 @@ extern SubscribeActuatorControlTargetRequestDefaultTypeInternal _SubscribeActuat class SubscribeActuatorOutputStatusRequest; struct SubscribeActuatorOutputStatusRequestDefaultTypeInternal; extern SubscribeActuatorOutputStatusRequestDefaultTypeInternal _SubscribeActuatorOutputStatusRequest_default_instance_; +class SubscribeAltitudeRequest; +struct SubscribeAltitudeRequestDefaultTypeInternal; +extern SubscribeAltitudeRequestDefaultTypeInternal _SubscribeAltitudeRequest_default_instance_; class SubscribeArmedRequest; struct SubscribeArmedRequestDefaultTypeInternal; extern SubscribeArmedRequestDefaultTypeInternal _SubscribeArmedRequest_default_instance_; @@ -506,6 +521,8 @@ template<> ::mavsdk::rpc::telemetry::ActuatorControlTarget* Arena::CreateMaybeMe template<> ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::ActuatorOutputStatus* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatus>(Arena*); template<> ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::Altitude* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::Altitude>(Arena*); +template<> ::mavsdk::rpc::telemetry::AltitudeResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AltitudeResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::AngularVelocityBody* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityBody>(Arena*); template<> ::mavsdk::rpc::telemetry::AngularVelocityFrd* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityFrd>(Arena*); template<> ::mavsdk::rpc::telemetry::ArmedResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ArmedResponse>(Arena*); @@ -562,6 +579,8 @@ template<> ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetRequest* Arena: template<> ::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateActuatorControlTargetResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateActuatorOutputStatusResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::SetRateAltitudeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateAltitudeRequest>(Arena*); +template<> ::mavsdk::rpc::telemetry::SetRateAltitudeResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateAltitudeResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateAttitudeAngularVelocityBodyResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SetRateAttitudeEulerRequest>(Arena*); @@ -613,6 +632,7 @@ template<> ::mavsdk::rpc::telemetry::StatusText* Arena::CreateMaybeMessage<::mav template<> ::mavsdk::rpc::telemetry::StatusTextResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::StatusTextResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest>(Arena*); +template<> ::mavsdk::rpc::telemetry::SubscribeAltitudeRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAltitudeRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeArmedRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeArmedRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest>(Arena*); @@ -9651,6 +9671,274 @@ class HeadingResponse final : }; // ------------------------------------------------------------------- +class SubscribeAltitudeRequest final : + public ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) */ { + public: + inline SubscribeAltitudeRequest() : SubscribeAltitudeRequest(nullptr) {} + explicit PROTOBUF_CONSTEXPR SubscribeAltitudeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SubscribeAltitudeRequest(const SubscribeAltitudeRequest& from); + SubscribeAltitudeRequest(SubscribeAltitudeRequest&& from) noexcept + : SubscribeAltitudeRequest() { + *this = ::std::move(from); + } + + inline SubscribeAltitudeRequest& operator=(const SubscribeAltitudeRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeAltitudeRequest& operator=(SubscribeAltitudeRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SubscribeAltitudeRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeAltitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAltitudeRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 66; + + friend void swap(SubscribeAltitudeRequest& a, SubscribeAltitudeRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeAltitudeRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeAltitudeRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeAltitudeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeAltitudeRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::CopyImpl(this, from); + } + using ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeAltitudeRequest& from) { + ::PROTOBUF_NAMESPACE_ID::internal::ZeroFieldsBase::MergeImpl(this, from); + } + public: + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.telemetry.SubscribeAltitudeRequest"; + } + protected: + explicit SubscribeAltitudeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAltitudeRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class AltitudeResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AltitudeResponse) */ { + public: + inline AltitudeResponse() : AltitudeResponse(nullptr) {} + ~AltitudeResponse() override; + explicit PROTOBUF_CONSTEXPR AltitudeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + AltitudeResponse(const AltitudeResponse& from); + AltitudeResponse(AltitudeResponse&& from) noexcept + : AltitudeResponse() { + *this = ::std::move(from); + } + + inline AltitudeResponse& operator=(const AltitudeResponse& from) { + CopyFrom(from); + return *this; + } + inline AltitudeResponse& operator=(AltitudeResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const AltitudeResponse& default_instance() { + return *internal_default_instance(); + } + static inline const AltitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_AltitudeResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 67; + + friend void swap(AltitudeResponse& a, AltitudeResponse& b) { + a.Swap(&b); + } + inline void Swap(AltitudeResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(AltitudeResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + AltitudeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const AltitudeResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const AltitudeResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + uint8_t* _InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(AltitudeResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.telemetry.AltitudeResponse"; + } + protected: + explicit AltitudeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kAltitudeFieldNumber = 1, + }; + // .mavsdk.rpc.telemetry.Altitude altitude = 1; + bool has_altitude() const; + private: + bool _internal_has_altitude() const; + public: + void clear_altitude(); + const ::mavsdk::rpc::telemetry::Altitude& altitude() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry::Altitude* release_altitude(); + ::mavsdk::rpc::telemetry::Altitude* mutable_altitude(); + void set_allocated_altitude(::mavsdk::rpc::telemetry::Altitude* altitude); + private: + const ::mavsdk::rpc::telemetry::Altitude& _internal_altitude() const; + ::mavsdk::rpc::telemetry::Altitude* _internal_mutable_altitude(); + public: + void unsafe_arena_set_allocated_altitude( + ::mavsdk::rpc::telemetry::Altitude* altitude); + ::mavsdk::rpc::telemetry::Altitude* unsafe_arena_release_altitude(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AltitudeResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::telemetry::Altitude* altitude_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + class SetRatePositionRequest final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRatePositionRequest) */ { public: @@ -9699,7 +9987,7 @@ class SetRatePositionRequest final : &_SetRatePositionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 66; + 68; friend void swap(SetRatePositionRequest& a, SetRatePositionRequest& b) { a.Swap(&b); @@ -9842,7 +10130,7 @@ class SetRatePositionResponse final : &_SetRatePositionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 67; + 69; friend void swap(SetRatePositionResponse& a, SetRatePositionResponse& b) { a.Swap(&b); @@ -9994,7 +10282,7 @@ class SetRateHomeRequest final : &_SetRateHomeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 68; + 70; friend void swap(SetRateHomeRequest& a, SetRateHomeRequest& b) { a.Swap(&b); @@ -10137,7 +10425,7 @@ class SetRateHomeResponse final : &_SetRateHomeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 69; + 71; friend void swap(SetRateHomeResponse& a, SetRateHomeResponse& b) { a.Swap(&b); @@ -10289,7 +10577,7 @@ class SetRateInAirRequest final : &_SetRateInAirRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 70; + 72; friend void swap(SetRateInAirRequest& a, SetRateInAirRequest& b) { a.Swap(&b); @@ -10432,7 +10720,7 @@ class SetRateInAirResponse final : &_SetRateInAirResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 71; + 73; friend void swap(SetRateInAirResponse& a, SetRateInAirResponse& b) { a.Swap(&b); @@ -10584,7 +10872,7 @@ class SetRateLandedStateRequest final : &_SetRateLandedStateRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 72; + 74; friend void swap(SetRateLandedStateRequest& a, SetRateLandedStateRequest& b) { a.Swap(&b); @@ -10727,7 +11015,7 @@ class SetRateLandedStateResponse final : &_SetRateLandedStateResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 73; + 75; friend void swap(SetRateLandedStateResponse& a, SetRateLandedStateResponse& b) { a.Swap(&b); @@ -10879,7 +11167,7 @@ class SetRateVtolStateRequest final : &_SetRateVtolStateRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 74; + 76; friend void swap(SetRateVtolStateRequest& a, SetRateVtolStateRequest& b) { a.Swap(&b); @@ -11022,7 +11310,7 @@ class SetRateVtolStateResponse final : &_SetRateVtolStateResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 75; + 77; friend void swap(SetRateVtolStateResponse& a, SetRateVtolStateResponse& b) { a.Swap(&b); @@ -11174,7 +11462,7 @@ class SetRateAttitudeEulerRequest final : &_SetRateAttitudeEulerRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 76; + 78; friend void swap(SetRateAttitudeEulerRequest& a, SetRateAttitudeEulerRequest& b) { a.Swap(&b); @@ -11317,7 +11605,7 @@ class SetRateAttitudeEulerResponse final : &_SetRateAttitudeEulerResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 77; + 79; friend void swap(SetRateAttitudeEulerResponse& a, SetRateAttitudeEulerResponse& b) { a.Swap(&b); @@ -11469,7 +11757,7 @@ class SetRateAttitudeQuaternionRequest final : &_SetRateAttitudeQuaternionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 78; + 80; friend void swap(SetRateAttitudeQuaternionRequest& a, SetRateAttitudeQuaternionRequest& b) { a.Swap(&b); @@ -11612,7 +11900,7 @@ class SetRateAttitudeQuaternionResponse final : &_SetRateAttitudeQuaternionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 79; + 81; friend void swap(SetRateAttitudeQuaternionResponse& a, SetRateAttitudeQuaternionResponse& b) { a.Swap(&b); @@ -11764,7 +12052,7 @@ class SetRateAttitudeAngularVelocityBodyRequest final : &_SetRateAttitudeAngularVelocityBodyRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 80; + 82; friend void swap(SetRateAttitudeAngularVelocityBodyRequest& a, SetRateAttitudeAngularVelocityBodyRequest& b) { a.Swap(&b); @@ -11907,7 +12195,7 @@ class SetRateAttitudeAngularVelocityBodyResponse final : &_SetRateAttitudeAngularVelocityBodyResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 81; + 83; friend void swap(SetRateAttitudeAngularVelocityBodyResponse& a, SetRateAttitudeAngularVelocityBodyResponse& b) { a.Swap(&b); @@ -12059,7 +12347,7 @@ class SetRateCameraAttitudeQuaternionRequest final : &_SetRateCameraAttitudeQuaternionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 82; + 84; friend void swap(SetRateCameraAttitudeQuaternionRequest& a, SetRateCameraAttitudeQuaternionRequest& b) { a.Swap(&b); @@ -12202,7 +12490,7 @@ class SetRateCameraAttitudeQuaternionResponse final : &_SetRateCameraAttitudeQuaternionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 83; + 85; friend void swap(SetRateCameraAttitudeQuaternionResponse& a, SetRateCameraAttitudeQuaternionResponse& b) { a.Swap(&b); @@ -12354,7 +12642,7 @@ class SetRateCameraAttitudeRequest final : &_SetRateCameraAttitudeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 84; + 86; friend void swap(SetRateCameraAttitudeRequest& a, SetRateCameraAttitudeRequest& b) { a.Swap(&b); @@ -12497,7 +12785,7 @@ class SetRateCameraAttitudeResponse final : &_SetRateCameraAttitudeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 85; + 87; friend void swap(SetRateCameraAttitudeResponse& a, SetRateCameraAttitudeResponse& b) { a.Swap(&b); @@ -12649,7 +12937,7 @@ class SetRateVelocityNedRequest final : &_SetRateVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 86; + 88; friend void swap(SetRateVelocityNedRequest& a, SetRateVelocityNedRequest& b) { a.Swap(&b); @@ -12792,7 +13080,7 @@ class SetRateVelocityNedResponse final : &_SetRateVelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 87; + 89; friend void swap(SetRateVelocityNedResponse& a, SetRateVelocityNedResponse& b) { a.Swap(&b); @@ -12944,7 +13232,7 @@ class SetRateGpsInfoRequest final : &_SetRateGpsInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 88; + 90; friend void swap(SetRateGpsInfoRequest& a, SetRateGpsInfoRequest& b) { a.Swap(&b); @@ -13087,7 +13375,7 @@ class SetRateGpsInfoResponse final : &_SetRateGpsInfoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 89; + 91; friend void swap(SetRateGpsInfoResponse& a, SetRateGpsInfoResponse& b) { a.Swap(&b); @@ -13239,7 +13527,7 @@ class SetRateRawGpsRequest final : &_SetRateRawGpsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 90; + 92; friend void swap(SetRateRawGpsRequest& a, SetRateRawGpsRequest& b) { a.Swap(&b); @@ -13382,7 +13670,7 @@ class SetRateBatteryRequest final : &_SetRateBatteryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 91; + 93; friend void swap(SetRateBatteryRequest& a, SetRateBatteryRequest& b) { a.Swap(&b); @@ -13525,7 +13813,7 @@ class SetRateBatteryResponse final : &_SetRateBatteryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 92; + 94; friend void swap(SetRateBatteryResponse& a, SetRateBatteryResponse& b) { a.Swap(&b); @@ -13677,7 +13965,7 @@ class SetRateRcStatusRequest final : &_SetRateRcStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 93; + 95; friend void swap(SetRateRcStatusRequest& a, SetRateRcStatusRequest& b) { a.Swap(&b); @@ -13820,7 +14108,7 @@ class SetRateRcStatusResponse final : &_SetRateRcStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 94; + 96; friend void swap(SetRateRcStatusResponse& a, SetRateRcStatusResponse& b) { a.Swap(&b); @@ -13972,7 +14260,7 @@ class SetRateActuatorControlTargetRequest final : &_SetRateActuatorControlTargetRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 95; + 97; friend void swap(SetRateActuatorControlTargetRequest& a, SetRateActuatorControlTargetRequest& b) { a.Swap(&b); @@ -14115,7 +14403,7 @@ class SetRateActuatorControlTargetResponse final : &_SetRateActuatorControlTargetResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 96; + 98; friend void swap(SetRateActuatorControlTargetResponse& a, SetRateActuatorControlTargetResponse& b) { a.Swap(&b); @@ -14267,7 +14555,7 @@ class SetRateActuatorOutputStatusRequest final : &_SetRateActuatorOutputStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 97; + 99; friend void swap(SetRateActuatorOutputStatusRequest& a, SetRateActuatorOutputStatusRequest& b) { a.Swap(&b); @@ -14410,7 +14698,7 @@ class SetRateActuatorOutputStatusResponse final : &_SetRateActuatorOutputStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 98; + 100; friend void swap(SetRateActuatorOutputStatusResponse& a, SetRateActuatorOutputStatusResponse& b) { a.Swap(&b); @@ -14562,7 +14850,7 @@ class SetRateOdometryRequest final : &_SetRateOdometryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 99; + 101; friend void swap(SetRateOdometryRequest& a, SetRateOdometryRequest& b) { a.Swap(&b); @@ -14705,7 +14993,7 @@ class SetRateOdometryResponse final : &_SetRateOdometryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 100; + 102; friend void swap(SetRateOdometryResponse& a, SetRateOdometryResponse& b) { a.Swap(&b); @@ -14857,7 +15145,7 @@ class SetRatePositionVelocityNedRequest final : &_SetRatePositionVelocityNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 101; + 103; friend void swap(SetRatePositionVelocityNedRequest& a, SetRatePositionVelocityNedRequest& b) { a.Swap(&b); @@ -15000,7 +15288,7 @@ class SetRatePositionVelocityNedResponse final : &_SetRatePositionVelocityNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 102; + 104; friend void swap(SetRatePositionVelocityNedResponse& a, SetRatePositionVelocityNedResponse& b) { a.Swap(&b); @@ -15152,7 +15440,7 @@ class SetRateGroundTruthRequest final : &_SetRateGroundTruthRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 103; + 105; friend void swap(SetRateGroundTruthRequest& a, SetRateGroundTruthRequest& b) { a.Swap(&b); @@ -15295,7 +15583,7 @@ class SetRateGroundTruthResponse final : &_SetRateGroundTruthResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 104; + 106; friend void swap(SetRateGroundTruthResponse& a, SetRateGroundTruthResponse& b) { a.Swap(&b); @@ -15447,7 +15735,7 @@ class SetRateFixedwingMetricsRequest final : &_SetRateFixedwingMetricsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 105; + 107; friend void swap(SetRateFixedwingMetricsRequest& a, SetRateFixedwingMetricsRequest& b) { a.Swap(&b); @@ -15590,7 +15878,7 @@ class SetRateFixedwingMetricsResponse final : &_SetRateFixedwingMetricsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 106; + 108; friend void swap(SetRateFixedwingMetricsResponse& a, SetRateFixedwingMetricsResponse& b) { a.Swap(&b); @@ -15742,7 +16030,7 @@ class SetRateImuRequest final : &_SetRateImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 107; + 109; friend void swap(SetRateImuRequest& a, SetRateImuRequest& b) { a.Swap(&b); @@ -15885,7 +16173,7 @@ class SetRateImuResponse final : &_SetRateImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 108; + 110; friend void swap(SetRateImuResponse& a, SetRateImuResponse& b) { a.Swap(&b); @@ -16037,7 +16325,7 @@ class SetRateScaledImuRequest final : &_SetRateScaledImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 109; + 111; friend void swap(SetRateScaledImuRequest& a, SetRateScaledImuRequest& b) { a.Swap(&b); @@ -16180,7 +16468,7 @@ class SetRateScaledImuResponse final : &_SetRateScaledImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 110; + 112; friend void swap(SetRateScaledImuResponse& a, SetRateScaledImuResponse& b) { a.Swap(&b); @@ -16332,7 +16620,7 @@ class SetRateRawImuRequest final : &_SetRateRawImuRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 111; + 113; friend void swap(SetRateRawImuRequest& a, SetRateRawImuRequest& b) { a.Swap(&b); @@ -16475,7 +16763,7 @@ class SetRateRawImuResponse final : &_SetRateRawImuResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 112; + 114; friend void swap(SetRateRawImuResponse& a, SetRateRawImuResponse& b) { a.Swap(&b); @@ -16627,7 +16915,7 @@ class SetRateUnixEpochTimeRequest final : &_SetRateUnixEpochTimeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 113; + 115; friend void swap(SetRateUnixEpochTimeRequest& a, SetRateUnixEpochTimeRequest& b) { a.Swap(&b); @@ -16770,7 +17058,7 @@ class SetRateUnixEpochTimeResponse final : &_SetRateUnixEpochTimeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 114; + 116; friend void swap(SetRateUnixEpochTimeResponse& a, SetRateUnixEpochTimeResponse& b) { a.Swap(&b); @@ -16922,7 +17210,7 @@ class SetRateDistanceSensorRequest final : &_SetRateDistanceSensorRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 115; + 117; friend void swap(SetRateDistanceSensorRequest& a, SetRateDistanceSensorRequest& b) { a.Swap(&b); @@ -17065,7 +17353,7 @@ class SetRateDistanceSensorResponse final : &_SetRateDistanceSensorResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 116; + 118; friend void swap(SetRateDistanceSensorResponse& a, SetRateDistanceSensorResponse& b) { a.Swap(&b); @@ -17216,7 +17504,7 @@ class GetGpsGlobalOriginRequest final : &_GetGpsGlobalOriginRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 117; + 119; friend void swap(GetGpsGlobalOriginRequest& a, GetGpsGlobalOriginRequest& b) { a.Swap(&b); @@ -17288,21 +17576,336 @@ class GetGpsGlobalOriginRequest final : class GetGpsGlobalOriginResponse final : public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) */ { public: - inline GetGpsGlobalOriginResponse() : GetGpsGlobalOriginResponse(nullptr) {} - ~GetGpsGlobalOriginResponse() override; - explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + inline GetGpsGlobalOriginResponse() : GetGpsGlobalOriginResponse(nullptr) {} + ~GetGpsGlobalOriginResponse() override; + explicit PROTOBUF_CONSTEXPR GetGpsGlobalOriginResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + GetGpsGlobalOriginResponse(const GetGpsGlobalOriginResponse& from); + GetGpsGlobalOriginResponse(GetGpsGlobalOriginResponse&& from) noexcept + : GetGpsGlobalOriginResponse() { + *this = ::std::move(from); + } + + inline GetGpsGlobalOriginResponse& operator=(const GetGpsGlobalOriginResponse& from) { + CopyFrom(from); + return *this; + } + inline GetGpsGlobalOriginResponse& operator=(GetGpsGlobalOriginResponse&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GetGpsGlobalOriginResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GetGpsGlobalOriginResponse* internal_default_instance() { + return reinterpret_cast( + &_GetGpsGlobalOriginResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 120; + + friend void swap(GetGpsGlobalOriginResponse& a, GetGpsGlobalOriginResponse& b) { + a.Swap(&b); + } + inline void Swap(GetGpsGlobalOriginResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GetGpsGlobalOriginResponse* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetGpsGlobalOriginResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const GetGpsGlobalOriginResponse& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const GetGpsGlobalOriginResponse& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + uint8_t* _InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(GetGpsGlobalOriginResponse* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse"; + } + protected: + explicit GetGpsGlobalOriginResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kTelemetryResultFieldNumber = 1, + kGpsGlobalOriginFieldNumber = 2, + }; + // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; + bool has_telemetry_result() const; + private: + bool _internal_has_telemetry_result() const; + public: + 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* telemetry_result); + private: + const ::mavsdk::rpc::telemetry::TelemetryResult& _internal_telemetry_result() const; + ::mavsdk::rpc::telemetry::TelemetryResult* _internal_mutable_telemetry_result(); + public: + void unsafe_arena_set_allocated_telemetry_result( + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result); + ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); + + // .mavsdk.rpc.telemetry.GpsGlobalOrigin gps_global_origin = 2; + bool has_gps_global_origin() const; + private: + bool _internal_has_gps_global_origin() const; + public: + 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* gps_global_origin); + private: + const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& _internal_gps_global_origin() const; + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* _internal_mutable_gps_global_origin(); + public: + void unsafe_arena_set_allocated_gps_global_origin( + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin); + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* unsafe_arena_release_gps_global_origin(); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; + ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class SetRateAltitudeRequest final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeRequest) */ { + public: + inline SetRateAltitudeRequest() : SetRateAltitudeRequest(nullptr) {} + ~SetRateAltitudeRequest() override; + explicit PROTOBUF_CONSTEXPR SetRateAltitudeRequest(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + SetRateAltitudeRequest(const SetRateAltitudeRequest& from); + SetRateAltitudeRequest(SetRateAltitudeRequest&& from) noexcept + : SetRateAltitudeRequest() { + *this = ::std::move(from); + } + + inline SetRateAltitudeRequest& operator=(const SetRateAltitudeRequest& from) { + CopyFrom(from); + return *this; + } + inline SetRateAltitudeRequest& operator=(SetRateAltitudeRequest&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SetRateAltitudeRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetRateAltitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_SetRateAltitudeRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 121; + + friend void swap(SetRateAltitudeRequest& a, SetRateAltitudeRequest& b) { + a.Swap(&b); + } + inline void Swap(SetRateAltitudeRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SetRateAltitudeRequest* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetRateAltitudeRequest* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const SetRateAltitudeRequest& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const SetRateAltitudeRequest& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + uint8_t* _InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SetRateAltitudeRequest* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.telemetry.SetRateAltitudeRequest"; + } + protected: + explicit SetRateAltitudeRequest(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + 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.SetRateAltitudeRequest) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + double rate_hz_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class SetRateAltitudeResponse final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SetRateAltitudeResponse) */ { + public: + inline SetRateAltitudeResponse() : SetRateAltitudeResponse(nullptr) {} + ~SetRateAltitudeResponse() override; + explicit PROTOBUF_CONSTEXPR SetRateAltitudeResponse(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - GetGpsGlobalOriginResponse(const GetGpsGlobalOriginResponse& from); - GetGpsGlobalOriginResponse(GetGpsGlobalOriginResponse&& from) noexcept - : GetGpsGlobalOriginResponse() { + SetRateAltitudeResponse(const SetRateAltitudeResponse& from); + SetRateAltitudeResponse(SetRateAltitudeResponse&& from) noexcept + : SetRateAltitudeResponse() { *this = ::std::move(from); } - inline GetGpsGlobalOriginResponse& operator=(const GetGpsGlobalOriginResponse& from) { + inline SetRateAltitudeResponse& operator=(const SetRateAltitudeResponse& from) { CopyFrom(from); return *this; } - inline GetGpsGlobalOriginResponse& operator=(GetGpsGlobalOriginResponse&& from) noexcept { + inline SetRateAltitudeResponse& operator=(SetRateAltitudeResponse&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -17325,20 +17928,20 @@ class GetGpsGlobalOriginResponse final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GetGpsGlobalOriginResponse& default_instance() { + static const SetRateAltitudeResponse& default_instance() { return *internal_default_instance(); } - static inline const GetGpsGlobalOriginResponse* internal_default_instance() { - return reinterpret_cast( - &_GetGpsGlobalOriginResponse_default_instance_); + static inline const SetRateAltitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRateAltitudeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 118; + 122; - friend void swap(GetGpsGlobalOriginResponse& a, GetGpsGlobalOriginResponse& b) { + friend void swap(SetRateAltitudeResponse& a, SetRateAltitudeResponse& b) { a.Swap(&b); } - inline void Swap(GetGpsGlobalOriginResponse* other) { + inline void Swap(SetRateAltitudeResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -17351,7 +17954,7 @@ class GetGpsGlobalOriginResponse final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GetGpsGlobalOriginResponse* other) { + void UnsafeArenaSwap(SetRateAltitudeResponse* other) { if (other == this) return; GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -17359,13 +17962,13 @@ class GetGpsGlobalOriginResponse final : // implements Message ---------------------------------------------- - GetGpsGlobalOriginResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRateAltitudeResponse* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const GetGpsGlobalOriginResponse& from); + void CopyFrom(const SetRateAltitudeResponse& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom(const GetGpsGlobalOriginResponse& from); + void MergeFrom(const SetRateAltitudeResponse& from); private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); public: @@ -17382,15 +17985,15 @@ class GetGpsGlobalOriginResponse final : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(GetGpsGlobalOriginResponse* other); + void InternalSwap(SetRateAltitudeResponse* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { - return "mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse"; + return "mavsdk.rpc.telemetry.SetRateAltitudeResponse"; } protected: - explicit GetGpsGlobalOriginResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, + explicit SetRateAltitudeResponse(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned = false); public: @@ -17405,7 +18008,6 @@ class GetGpsGlobalOriginResponse final : enum : int { kTelemetryResultFieldNumber = 1, - kGpsGlobalOriginFieldNumber = 2, }; // .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; bool has_telemetry_result() const; @@ -17425,25 +18027,7 @@ class GetGpsGlobalOriginResponse final : ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result); ::mavsdk::rpc::telemetry::TelemetryResult* unsafe_arena_release_telemetry_result(); - // .mavsdk.rpc.telemetry.GpsGlobalOrigin gps_global_origin = 2; - bool has_gps_global_origin() const; - private: - bool _internal_has_gps_global_origin() const; - public: - 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* gps_global_origin); - private: - const ::mavsdk::rpc::telemetry::GpsGlobalOrigin& _internal_gps_global_origin() const; - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* _internal_mutable_gps_global_origin(); - public: - void unsafe_arena_set_allocated_gps_global_origin( - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin); - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* unsafe_arena_release_gps_global_origin(); - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GetGpsGlobalOriginResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SetRateAltitudeResponse) private: class _Internal; @@ -17451,7 +18035,6 @@ class GetGpsGlobalOriginResponse final : typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result_; - ::mavsdk::rpc::telemetry::GpsGlobalOrigin* gps_global_origin_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; @@ -17505,7 +18088,7 @@ class Position final : &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 119; + 123; friend void swap(Position& a, Position& b) { a.Swap(&b); @@ -17681,7 +18264,7 @@ class Heading final : &_Heading_default_instance_); } static constexpr int kIndexInFileMessages = - 120; + 124; friend void swap(Heading& a, Heading& b) { a.Swap(&b); @@ -17824,7 +18407,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 121; + 125; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -18011,7 +18594,7 @@ class EulerAngle final : &_EulerAngle_default_instance_); } static constexpr int kIndexInFileMessages = - 122; + 126; friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); @@ -18187,7 +18770,7 @@ class AngularVelocityBody final : &_AngularVelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 123; + 127; friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { a.Swap(&b); @@ -18352,7 +18935,7 @@ class GpsInfo final : &_GpsInfo_default_instance_); } static constexpr int kIndexInFileMessages = - 124; + 128; friend void swap(GpsInfo& a, GpsInfo& b) { a.Swap(&b); @@ -18506,7 +19089,7 @@ class RawGps final : &_RawGps_default_instance_); } static constexpr int kIndexInFileMessages = - 125; + 129; friend void swap(RawGps& a, RawGps& b) { a.Swap(&b); @@ -18792,7 +19375,7 @@ class Battery final : &_Battery_default_instance_); } static constexpr int kIndexInFileMessages = - 126; + 130; friend void swap(Battery& a, Battery& b) { a.Swap(&b); @@ -18957,7 +19540,7 @@ class Health final : &_Health_default_instance_); } static constexpr int kIndexInFileMessages = - 127; + 131; friend void swap(Health& a, Health& b) { a.Swap(&b); @@ -19166,7 +19749,7 @@ class RcStatus final : &_RcStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 128; + 132; friend void swap(RcStatus& a, RcStatus& b) { a.Swap(&b); @@ -19331,7 +19914,7 @@ class StatusText final : &_StatusText_default_instance_); } static constexpr int kIndexInFileMessages = - 129; + 133; friend void swap(StatusText& a, StatusText& b) { a.Swap(&b); @@ -19490,7 +20073,7 @@ class ActuatorControlTarget final : &_ActuatorControlTarget_default_instance_); } static constexpr int kIndexInFileMessages = - 130; + 134; friend void swap(ActuatorControlTarget& a, ActuatorControlTarget& b) { a.Swap(&b); @@ -19657,7 +20240,7 @@ class ActuatorOutputStatus final : &_ActuatorOutputStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 131; + 135; friend void swap(ActuatorOutputStatus& a, ActuatorOutputStatus& b) { a.Swap(&b); @@ -19824,7 +20407,7 @@ class Covariance final : &_Covariance_default_instance_); } static constexpr int kIndexInFileMessages = - 132; + 136; friend void swap(Covariance& a, Covariance& b) { a.Swap(&b); @@ -19980,7 +20563,7 @@ class VelocityBody final : &_VelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 133; + 137; friend void swap(VelocityBody& a, VelocityBody& b) { a.Swap(&b); @@ -20145,7 +20728,7 @@ class PositionBody final : &_PositionBody_default_instance_); } static constexpr int kIndexInFileMessages = - 134; + 138; friend void swap(PositionBody& a, PositionBody& b) { a.Swap(&b); @@ -20310,7 +20893,7 @@ class Odometry final : &_Odometry_default_instance_); } static constexpr int kIndexInFileMessages = - 135; + 139; friend void swap(Odometry& a, Odometry& b) { a.Swap(&b); @@ -20629,7 +21212,7 @@ class DistanceSensor final : &_DistanceSensor_default_instance_); } static constexpr int kIndexInFileMessages = - 136; + 140; friend void swap(DistanceSensor& a, DistanceSensor& b) { a.Swap(&b); @@ -20794,7 +21377,7 @@ class ScaledPressure final : &_ScaledPressure_default_instance_); } static constexpr int kIndexInFileMessages = - 137; + 141; friend void swap(ScaledPressure& a, ScaledPressure& b) { a.Swap(&b); @@ -20981,7 +21564,7 @@ class PositionNed final : &_PositionNed_default_instance_); } static constexpr int kIndexInFileMessages = - 138; + 142; friend void swap(PositionNed& a, PositionNed& b) { a.Swap(&b); @@ -21146,7 +21729,7 @@ class VelocityNed final : &_VelocityNed_default_instance_); } static constexpr int kIndexInFileMessages = - 139; + 143; friend void swap(VelocityNed& a, VelocityNed& b) { a.Swap(&b); @@ -21311,7 +21894,7 @@ class PositionVelocityNed final : &_PositionVelocityNed_default_instance_); } static constexpr int kIndexInFileMessages = - 140; + 144; friend void swap(PositionVelocityNed& a, PositionVelocityNed& b) { a.Swap(&b); @@ -21483,7 +22066,7 @@ class GroundTruth final : &_GroundTruth_default_instance_); } static constexpr int kIndexInFileMessages = - 141; + 145; friend void swap(GroundTruth& a, GroundTruth& b) { a.Swap(&b); @@ -21648,7 +22231,7 @@ class FixedwingMetrics final : &_FixedwingMetrics_default_instance_); } static constexpr int kIndexInFileMessages = - 142; + 146; friend void swap(FixedwingMetrics& a, FixedwingMetrics& b) { a.Swap(&b); @@ -21813,7 +22396,7 @@ class AccelerationFrd final : &_AccelerationFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 143; + 147; friend void swap(AccelerationFrd& a, AccelerationFrd& b) { a.Swap(&b); @@ -21978,7 +22561,7 @@ class AngularVelocityFrd final : &_AngularVelocityFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 144; + 148; friend void swap(AngularVelocityFrd& a, AngularVelocityFrd& b) { a.Swap(&b); @@ -22143,7 +22726,7 @@ class MagneticFieldFrd final : &_MagneticFieldFrd_default_instance_); } static constexpr int kIndexInFileMessages = - 145; + 149; friend void swap(MagneticFieldFrd& a, MagneticFieldFrd& b) { a.Swap(&b); @@ -22308,7 +22891,7 @@ class Imu final : &_Imu_default_instance_); } static constexpr int kIndexInFileMessages = - 146; + 150; friend void swap(Imu& a, Imu& b) { a.Swap(&b); @@ -22474,24 +23057,189 @@ class Imu final : }; // ------------------------------------------------------------------- -class GpsGlobalOrigin final : - public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsGlobalOrigin) */ { +class GpsGlobalOrigin final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsGlobalOrigin) */ { + public: + inline GpsGlobalOrigin() : GpsGlobalOrigin(nullptr) {} + ~GpsGlobalOrigin() override; + explicit PROTOBUF_CONSTEXPR GpsGlobalOrigin(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + + GpsGlobalOrigin(const GpsGlobalOrigin& from); + GpsGlobalOrigin(GpsGlobalOrigin&& from) noexcept + : GpsGlobalOrigin() { + *this = ::std::move(from); + } + + inline GpsGlobalOrigin& operator=(const GpsGlobalOrigin& from) { + CopyFrom(from); + return *this; + } + inline GpsGlobalOrigin& operator=(GpsGlobalOrigin&& from) noexcept { + if (this == &from) return *this; + if (GetOwningArena() == from.GetOwningArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetOwningArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GpsGlobalOrigin& default_instance() { + return *internal_default_instance(); + } + static inline const GpsGlobalOrigin* internal_default_instance() { + return reinterpret_cast( + &_GpsGlobalOrigin_default_instance_); + } + static constexpr int kIndexInFileMessages = + 151; + + friend void swap(GpsGlobalOrigin& a, GpsGlobalOrigin& b) { + a.Swap(&b); + } + inline void Swap(GpsGlobalOrigin* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() != nullptr && + GetOwningArena() == other->GetOwningArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetOwningArena() == other->GetOwningArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GpsGlobalOrigin* other) { + if (other == this) return; + GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GpsGlobalOrigin* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; + void CopyFrom(const GpsGlobalOrigin& from); + using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; + void MergeFrom(const GpsGlobalOrigin& from); + private: + static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final; + uint8_t* _InternalSerialize( + uint8_t* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(GpsGlobalOrigin* other); + + private: + friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; + static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { + return "mavsdk.rpc.telemetry.GpsGlobalOrigin"; + } + protected: + explicit GpsGlobalOrigin(::PROTOBUF_NAMESPACE_ID::Arena* arena, + bool is_message_owned = false); + public: + + static const ClassData _class_data_; + const ::PROTOBUF_NAMESPACE_ID::Message::ClassData*GetClassData() const final; + + ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kLatitudeDegFieldNumber = 1, + kLongitudeDegFieldNumber = 2, + kAltitudeMFieldNumber = 3, + }; + // 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 altitude_m = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_altitude_m(); + float altitude_m() const; + void set_altitude_m(float value); + private: + float _internal_altitude_m() const; + void _internal_set_altitude_m(float value); + public: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsGlobalOrigin) + private: + class _Internal; + + template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; + typedef void InternalArenaConstructable_; + typedef void DestructorSkippable_; + double latitude_deg_; + double longitude_deg_; + float altitude_m_; + mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class Altitude final : + public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Altitude) */ { public: - inline GpsGlobalOrigin() : GpsGlobalOrigin(nullptr) {} - ~GpsGlobalOrigin() override; - explicit PROTOBUF_CONSTEXPR GpsGlobalOrigin(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); + inline Altitude() : Altitude(nullptr) {} + ~Altitude() override; + explicit PROTOBUF_CONSTEXPR Altitude(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized); - GpsGlobalOrigin(const GpsGlobalOrigin& from); - GpsGlobalOrigin(GpsGlobalOrigin&& from) noexcept - : GpsGlobalOrigin() { + Altitude(const Altitude& from); + Altitude(Altitude&& from) noexcept + : Altitude() { *this = ::std::move(from); } - inline GpsGlobalOrigin& operator=(const GpsGlobalOrigin& from) { + inline Altitude& operator=(const Altitude& from) { CopyFrom(from); return *this; } - inline GpsGlobalOrigin& operator=(GpsGlobalOrigin&& from) noexcept { + inline Altitude& operator=(Altitude&& from) noexcept { if (this == &from) return *this; if (GetOwningArena() == from.GetOwningArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -22514,20 +23262,20 @@ class GpsGlobalOrigin final : static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const GpsGlobalOrigin& default_instance() { + static const Altitude& default_instance() { return *internal_default_instance(); } - static inline const GpsGlobalOrigin* internal_default_instance() { - return reinterpret_cast( - &_GpsGlobalOrigin_default_instance_); + static inline const Altitude* internal_default_instance() { + return reinterpret_cast( + &_Altitude_default_instance_); } static constexpr int kIndexInFileMessages = - 147; + 152; - friend void swap(GpsGlobalOrigin& a, GpsGlobalOrigin& b) { + friend void swap(Altitude& a, Altitude& b) { a.Swap(&b); } - inline void Swap(GpsGlobalOrigin* other) { + inline void Swap(Altitude* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetOwningArena() != nullptr && @@ -22540,7 +23288,7 @@ class GpsGlobalOrigin final : ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(GpsGlobalOrigin* other) { + void UnsafeArenaSwap(Altitude* other) { if (other == this) return; GOOGLE_DCHECK(GetOwningArena() == other->GetOwningArena()); InternalSwap(other); @@ -22548,13 +23296,13 @@ class GpsGlobalOrigin final : // implements Message ---------------------------------------------- - GpsGlobalOrigin* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + Altitude* New(::PROTOBUF_NAMESPACE_ID::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::PROTOBUF_NAMESPACE_ID::Message::CopyFrom; - void CopyFrom(const GpsGlobalOrigin& from); + void CopyFrom(const Altitude& from); using ::PROTOBUF_NAMESPACE_ID::Message::MergeFrom; - void MergeFrom(const GpsGlobalOrigin& from); + void MergeFrom(const Altitude& from); private: static void MergeImpl(::PROTOBUF_NAMESPACE_ID::Message* to, const ::PROTOBUF_NAMESPACE_ID::Message& from); public: @@ -22571,15 +23319,15 @@ class GpsGlobalOrigin final : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(GpsGlobalOrigin* other); + void InternalSwap(Altitude* other); private: friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata; static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() { - return "mavsdk.rpc.telemetry.GpsGlobalOrigin"; + return "mavsdk.rpc.telemetry.Altitude"; } protected: - explicit GpsGlobalOrigin(::PROTOBUF_NAMESPACE_ID::Arena* arena, + explicit Altitude(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned = false); public: @@ -22593,47 +23341,69 @@ class GpsGlobalOrigin final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAltitudeMFieldNumber = 3, + kAltitudeMonotonicMFieldNumber = 1, + kAltitudeAmslMFieldNumber = 2, + kAltitudeLocalMFieldNumber = 3, + kAltitudeRelativeMFieldNumber = 4, + kAltitudeTerrainMFieldNumber = 5, }; - // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_latitude_deg(); - double latitude_deg() const; - void set_latitude_deg(double 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: - double _internal_latitude_deg() const; - void _internal_set_latitude_deg(double value); + float _internal_altitude_monotonic_m() const; + void _internal_set_altitude_monotonic_m(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 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: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); + float _internal_altitude_amsl_m() const; + void _internal_set_altitude_amsl_m(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); + // 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_m() const; - void _internal_set_altitude_m(float value); + float _internal_altitude_local_m() const; + void _internal_set_altitude_local_m(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsGlobalOrigin) + // 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: + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Altitude) private: class _Internal; template friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper; typedef void InternalArenaConstructable_; typedef void DestructorSkippable_; - double latitude_deg_; - double longitude_deg_; - float altitude_m_; + float altitude_monotonic_m_; + float altitude_amsl_m_; + float altitude_local_m_; + float altitude_relative_m_; + float altitude_terrain_m_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; @@ -22687,7 +23457,7 @@ class TelemetryResult final : &_TelemetryResult_default_instance_); } static constexpr int kIndexInFileMessages = - 148; + 153; friend void swap(TelemetryResult& a, TelemetryResult& b) { a.Swap(&b); @@ -25591,6 +26361,104 @@ inline void HeadingResponse::set_allocated_heading_deg(::mavsdk::rpc::telemetry: // ------------------------------------------------------------------- +// SubscribeAltitudeRequest + +// ------------------------------------------------------------------- + +// AltitudeResponse + +// .mavsdk.rpc.telemetry.Altitude altitude = 1; +inline bool AltitudeResponse::_internal_has_altitude() const { + return this != internal_default_instance() && altitude_ != nullptr; +} +inline bool AltitudeResponse::has_altitude() const { + return _internal_has_altitude(); +} +inline void AltitudeResponse::clear_altitude() { + if (GetArenaForAllocation() == nullptr && altitude_ != nullptr) { + delete altitude_; + } + altitude_ = nullptr; +} +inline const ::mavsdk::rpc::telemetry::Altitude& AltitudeResponse::_internal_altitude() const { + const ::mavsdk::rpc::telemetry::Altitude* p = altitude_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::telemetry::_Altitude_default_instance_); +} +inline const ::mavsdk::rpc::telemetry::Altitude& AltitudeResponse::altitude() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AltitudeResponse.altitude) + return _internal_altitude(); +} +inline void AltitudeResponse::unsafe_arena_set_allocated_altitude( + ::mavsdk::rpc::telemetry::Altitude* altitude) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(altitude_); + } + altitude_ = altitude; + if (altitude) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.AltitudeResponse.altitude) +} +inline ::mavsdk::rpc::telemetry::Altitude* AltitudeResponse::release_altitude() { + + ::mavsdk::rpc::telemetry::Altitude* temp = altitude_; + altitude_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::telemetry::Altitude* AltitudeResponse::unsafe_arena_release_altitude() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.AltitudeResponse.altitude) + + ::mavsdk::rpc::telemetry::Altitude* temp = altitude_; + altitude_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry::Altitude* AltitudeResponse::_internal_mutable_altitude() { + + if (altitude_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::Altitude>(GetArenaForAllocation()); + altitude_ = p; + } + return altitude_; +} +inline ::mavsdk::rpc::telemetry::Altitude* AltitudeResponse::mutable_altitude() { + ::mavsdk::rpc::telemetry::Altitude* _msg = _internal_mutable_altitude(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.AltitudeResponse.altitude) + return _msg; +} +inline void AltitudeResponse::set_allocated_altitude(::mavsdk::rpc::telemetry::Altitude* altitude) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete altitude_; + } + if (altitude) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(altitude); + if (message_arena != submessage_arena) { + altitude = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, altitude, submessage_arena); + } + + } else { + + } + altitude_ = altitude; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.AltitudeResponse.altitude) +} + +// ------------------------------------------------------------------- + // SetRatePositionRequest // double rate_hz = 1; @@ -28753,6 +29621,124 @@ inline void GetGpsGlobalOriginResponse::set_allocated_gps_global_origin(::mavsdk // ------------------------------------------------------------------- +// SetRateAltitudeRequest + +// double rate_hz = 1; +inline void SetRateAltitudeRequest::clear_rate_hz() { + rate_hz_ = 0; +} +inline double SetRateAltitudeRequest::_internal_rate_hz() const { + return rate_hz_; +} +inline double SetRateAltitudeRequest::rate_hz() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateAltitudeRequest.rate_hz) + return _internal_rate_hz(); +} +inline void SetRateAltitudeRequest::_internal_set_rate_hz(double value) { + + rate_hz_ = value; +} +inline void SetRateAltitudeRequest::set_rate_hz(double value) { + _internal_set_rate_hz(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.SetRateAltitudeRequest.rate_hz) +} + +// ------------------------------------------------------------------- + +// SetRateAltitudeResponse + +// .mavsdk.rpc.telemetry.TelemetryResult telemetry_result = 1; +inline bool SetRateAltitudeResponse::_internal_has_telemetry_result() const { + return this != internal_default_instance() && telemetry_result_ != nullptr; +} +inline bool SetRateAltitudeResponse::has_telemetry_result() const { + return _internal_has_telemetry_result(); +} +inline void SetRateAltitudeResponse::clear_telemetry_result() { + if (GetArenaForAllocation() == nullptr && telemetry_result_ != nullptr) { + delete telemetry_result_; + } + telemetry_result_ = nullptr; +} +inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAltitudeResponse::_internal_telemetry_result() const { + const ::mavsdk::rpc::telemetry::TelemetryResult* p = telemetry_result_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::telemetry::_TelemetryResult_default_instance_); +} +inline const ::mavsdk::rpc::telemetry::TelemetryResult& SetRateAltitudeResponse::telemetry_result() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.SetRateAltitudeResponse.telemetry_result) + return _internal_telemetry_result(); +} +inline void SetRateAltitudeResponse::unsafe_arena_set_allocated_telemetry_result( + ::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(telemetry_result_); + } + telemetry_result_ = telemetry_result; + if (telemetry_result) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry.SetRateAltitudeResponse.telemetry_result) +} +inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateAltitudeResponse::release_telemetry_result() { + + ::mavsdk::rpc::telemetry::TelemetryResult* temp = telemetry_result_; + telemetry_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateAltitudeResponse::unsafe_arena_release_telemetry_result() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.SetRateAltitudeResponse.telemetry_result) + + ::mavsdk::rpc::telemetry::TelemetryResult* temp = telemetry_result_; + telemetry_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateAltitudeResponse::_internal_mutable_telemetry_result() { + + if (telemetry_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::TelemetryResult>(GetArenaForAllocation()); + telemetry_result_ = p; + } + return telemetry_result_; +} +inline ::mavsdk::rpc::telemetry::TelemetryResult* SetRateAltitudeResponse::mutable_telemetry_result() { + ::mavsdk::rpc::telemetry::TelemetryResult* _msg = _internal_mutable_telemetry_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.SetRateAltitudeResponse.telemetry_result) + return _msg; +} +inline void SetRateAltitudeResponse::set_allocated_telemetry_result(::mavsdk::rpc::telemetry::TelemetryResult* telemetry_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete telemetry_result_; + } + if (telemetry_result) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalGetOwningArena(telemetry_result); + if (message_arena != submessage_arena) { + telemetry_result = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, telemetry_result, submessage_arena); + } + + } else { + + } + telemetry_result_ = telemetry_result; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.SetRateAltitudeResponse.telemetry_result) +} + +// ------------------------------------------------------------------- + // Position // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; @@ -31890,6 +32876,110 @@ inline void GpsGlobalOrigin::set_altitude_m(float value) { // ------------------------------------------------------------------- +// Altitude + +// float altitude_monotonic_m = 1 [(.mavsdk.options.default_value) = "NaN"]; +inline void Altitude::clear_altitude_monotonic_m() { + altitude_monotonic_m_ = 0; +} +inline float Altitude::_internal_altitude_monotonic_m() const { + return altitude_monotonic_m_; +} +inline float Altitude::altitude_monotonic_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.Altitude.altitude_monotonic_m) + return _internal_altitude_monotonic_m(); +} +inline void Altitude::_internal_set_altitude_monotonic_m(float value) { + + altitude_monotonic_m_ = value; +} +inline void Altitude::set_altitude_monotonic_m(float value) { + _internal_set_altitude_monotonic_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.Altitude.altitude_monotonic_m) +} + +// float altitude_amsl_m = 2 [(.mavsdk.options.default_value) = "NaN"]; +inline void Altitude::clear_altitude_amsl_m() { + altitude_amsl_m_ = 0; +} +inline float Altitude::_internal_altitude_amsl_m() const { + return altitude_amsl_m_; +} +inline float Altitude::altitude_amsl_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.Altitude.altitude_amsl_m) + return _internal_altitude_amsl_m(); +} +inline void Altitude::_internal_set_altitude_amsl_m(float value) { + + altitude_amsl_m_ = value; +} +inline void Altitude::set_altitude_amsl_m(float value) { + _internal_set_altitude_amsl_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.Altitude.altitude_amsl_m) +} + +// float altitude_local_m = 3 [(.mavsdk.options.default_value) = "NaN"]; +inline void Altitude::clear_altitude_local_m() { + altitude_local_m_ = 0; +} +inline float Altitude::_internal_altitude_local_m() const { + return altitude_local_m_; +} +inline float Altitude::altitude_local_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.Altitude.altitude_local_m) + return _internal_altitude_local_m(); +} +inline void Altitude::_internal_set_altitude_local_m(float value) { + + altitude_local_m_ = value; +} +inline void Altitude::set_altitude_local_m(float value) { + _internal_set_altitude_local_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.Altitude.altitude_local_m) +} + +// float altitude_relative_m = 4 [(.mavsdk.options.default_value) = "NaN"]; +inline void Altitude::clear_altitude_relative_m() { + altitude_relative_m_ = 0; +} +inline float Altitude::_internal_altitude_relative_m() const { + return altitude_relative_m_; +} +inline float Altitude::altitude_relative_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.Altitude.altitude_relative_m) + return _internal_altitude_relative_m(); +} +inline void Altitude::_internal_set_altitude_relative_m(float value) { + + altitude_relative_m_ = value; +} +inline void Altitude::set_altitude_relative_m(float value) { + _internal_set_altitude_relative_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.Altitude.altitude_relative_m) +} + +// float altitude_terrain_m = 5 [(.mavsdk.options.default_value) = "NaN"]; +inline void Altitude::clear_altitude_terrain_m() { + altitude_terrain_m_ = 0; +} +inline float Altitude::_internal_altitude_terrain_m() const { + return altitude_terrain_m_; +} +inline float Altitude::altitude_terrain_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.Altitude.altitude_terrain_m) + return _internal_altitude_terrain_m(); +} +inline void Altitude::_internal_set_altitude_terrain_m(float value) { + + altitude_terrain_m_ = value; +} +inline void Altitude::set_altitude_terrain_m(float value) { + _internal_set_altitude_terrain_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.Altitude.altitude_terrain_m) +} + +// ------------------------------------------------------------------- + // TelemetryResult // .mavsdk.rpc.telemetry.TelemetryResult.Result result = 1; @@ -32261,6 +33351,16 @@ inline void TelemetryResult::set_allocated_result_str(std::string* result_str) { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) 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 7e875e00bf..e260720722 100644 --- a/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h @@ -1252,6 +1252,42 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv return obj; } + static std::unique_ptr + translateToRpcAltitude(const mavsdk::Telemetry::Altitude& altitude) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_altitude_monotonic_m(altitude.altitude_monotonic_m); + + rpc_obj->set_altitude_amsl_m(altitude.altitude_amsl_m); + + rpc_obj->set_altitude_local_m(altitude.altitude_local_m); + + rpc_obj->set_altitude_relative_m(altitude.altitude_relative_m); + + rpc_obj->set_altitude_terrain_m(altitude.altitude_terrain_m); + + return rpc_obj; + } + + static mavsdk::Telemetry::Altitude + translateFromRpcAltitude(const rpc::telemetry::Altitude& altitude) + { + mavsdk::Telemetry::Altitude obj; + + obj.altitude_monotonic_m = altitude.altitude_monotonic_m(); + + obj.altitude_amsl_m = altitude.altitude_amsl_m(); + + obj.altitude_local_m = altitude.altitude_local_m(); + + obj.altitude_relative_m = altitude.altitude_relative_m(); + + obj.altitude_terrain_m = altitude.altitude_terrain_m(); + + return obj; + } + static rpc::telemetry::TelemetryResult::Result translateToRpcResult(const mavsdk::Telemetry::Result& result) { @@ -2671,6 +2707,47 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv return grpc::Status::OK; } + grpc::Status SubscribeAltitude( + grpc::ServerContext* /* context */, + const mavsdk::rpc::telemetry::SubscribeAltitudeRequest* /* 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::AltitudeHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_altitude( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::Telemetry::Altitude altitude) { + rpc::telemetry::AltitudeResponse rpc_response; + + rpc_response.set_allocated_altitude(translateToRpcAltitude(altitude).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_altitude(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 SetRatePosition( grpc::ServerContext* /* context */, const rpc::telemetry::SetRatePositionRequest* request, @@ -3318,6 +3395,34 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv return grpc::Status::OK; } + grpc::Status SetRateAltitude( + grpc::ServerContext* /* context */, + const rpc::telemetry::SetRateAltitudeRequest* request, + rpc::telemetry::SetRateAltitudeResponse* 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() << "SetRateAltitude sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_rate_altitude(request->rate_hz()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status GetGpsGlobalOrigin( grpc::ServerContext* /* context */, const rpc::telemetry::GetGpsGlobalOriginRequest* /* request */,