#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribePositionRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionResponse {
#[prost(message, optional, tag = "1")]
pub position: ::core::option::Option<Position>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeHomeRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct HomeResponse {
#[prost(message, optional, tag = "1")]
pub home: ::core::option::Option<Position>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeInAirRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct InAirResponse {
#[prost(bool, tag = "1")]
pub is_in_air: bool,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeLandedStateRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct LandedStateResponse {
#[prost(enumeration = "LandedState", tag = "1")]
pub landed_state: i32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeArmedRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ArmedResponse {
#[prost(bool, tag = "1")]
pub is_armed: bool,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeAttitudeQuaternionRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AttitudeQuaternionResponse {
#[prost(message, optional, tag = "1")]
pub attitude_quaternion: ::core::option::Option<Quaternion>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeAttitudeEulerRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AttitudeEulerResponse {
#[prost(message, optional, tag = "1")]
pub attitude_euler: ::core::option::Option<EulerAngle>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeAttitudeAngularVelocityBodyRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AttitudeAngularVelocityBodyResponse {
#[prost(message, optional, tag = "1")]
pub attitude_angular_velocity_body: ::core::option::Option<AngularVelocityBody>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeCameraAttitudeQuaternionRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct CameraAttitudeQuaternionResponse {
#[prost(message, optional, tag = "1")]
pub attitude_quaternion: ::core::option::Option<Quaternion>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeCameraAttitudeEulerRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct CameraAttitudeEulerResponse {
#[prost(message, optional, tag = "1")]
pub attitude_euler: ::core::option::Option<EulerAngle>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeVelocityNedRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct VelocityNedResponse {
#[prost(message, optional, tag = "1")]
pub velocity_ned: ::core::option::Option<VelocityNed>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeGpsInfoRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GpsInfoResponse {
#[prost(message, optional, tag = "1")]
pub gps_info: ::core::option::Option<GpsInfo>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeBatteryRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct BatteryResponse {
#[prost(message, optional, tag = "1")]
pub battery: ::core::option::Option<Battery>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeFlightModeRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct FlightModeResponse {
#[prost(enumeration = "FlightMode", tag = "1")]
pub flight_mode: i32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeHealthRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct HealthResponse {
#[prost(message, optional, tag = "1")]
pub health: ::core::option::Option<Health>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeRcStatusRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct RcStatusResponse {
#[prost(message, optional, tag = "1")]
pub rc_status: ::core::option::Option<RcStatus>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeStatusTextRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct StatusTextResponse {
#[prost(message, optional, tag = "1")]
pub status_text: ::core::option::Option<StatusText>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeActuatorControlTargetRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ActuatorControlTargetResponse {
#[prost(message, optional, tag = "1")]
pub actuator_control_target: ::core::option::Option<ActuatorControlTarget>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeActuatorOutputStatusRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ActuatorOutputStatusResponse {
#[prost(message, optional, tag = "1")]
pub actuator_output_status: ::core::option::Option<ActuatorOutputStatus>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeOdometryRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct OdometryResponse {
#[prost(message, optional, tag = "1")]
pub odometry: ::core::option::Option<Odometry>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribePositionVelocityNedRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionVelocityNedResponse {
#[prost(message, optional, tag = "1")]
pub position_velocity_ned: ::core::option::Option<PositionVelocityNed>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeGroundTruthRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GroundTruthResponse {
#[prost(message, optional, tag = "1")]
pub ground_truth: ::core::option::Option<GroundTruth>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeFixedwingMetricsRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct FixedwingMetricsResponse {
#[prost(message, optional, tag = "1")]
pub fixedwing_metrics: ::core::option::Option<FixedwingMetrics>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeImuRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ImuResponse {
#[prost(message, optional, tag = "1")]
pub imu: ::core::option::Option<Imu>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeHealthAllOkRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct HealthAllOkResponse {
#[prost(bool, tag = "1")]
pub is_health_all_ok: bool,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeUnixEpochTimeRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct UnixEpochTimeResponse {
#[prost(uint64, tag = "1")]
pub time_us: u64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SubscribeDistanceSensorRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct DistanceSensorResponse {
#[prost(message, optional, tag = "1")]
pub distance_sensor: ::core::option::Option<DistanceSensor>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRatePositionRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRatePositionResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateHomeRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateHomeResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateInAirRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateInAirResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateLandedStateRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateLandedStateResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateAttitudeRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateAttitudeResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateAttitudeAngularVelocityBodyRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateAttitudeAngularVelocityBodyResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateCameraAttitudeQuaternionRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateCameraAttitudeQuaternionResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateCameraAttitudeRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateCameraAttitudeResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateVelocityNedRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateVelocityNedResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateGpsInfoRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateGpsInfoResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateBatteryRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateBatteryResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateRcStatusRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateRcStatusResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateActuatorControlTargetRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateActuatorControlTargetResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateActuatorOutputStatusRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateActuatorOutputStatusResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateOdometryRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateOdometryResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRatePositionVelocityNedRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRatePositionVelocityNedResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateGroundTruthRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateGroundTruthResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateFixedwingMetricsRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateFixedwingMetricsResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateImuRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateImuResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateUnixEpochTimeRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateUnixEpochTimeResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateDistanceSensorRequest {
#[prost(double, tag = "1")]
pub rate_hz: f64,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetRateDistanceSensorResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GetGpsGlobalOriginRequest {}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GetGpsGlobalOriginResponse {
#[prost(message, optional, tag = "1")]
pub telemetry_result: ::core::option::Option<TelemetryResult>,
#[prost(message, optional, tag = "2")]
pub gps_global_origin: ::core::option::Option<GpsGlobalOrigin>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Position {
#[prost(double, tag = "1")]
pub latitude_deg: f64,
#[prost(double, tag = "2")]
pub longitude_deg: f64,
#[prost(float, tag = "3")]
pub absolute_altitude_m: f32,
#[prost(float, tag = "4")]
pub relative_altitude_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Quaternion {
#[prost(float, tag = "1")]
pub w: f32,
#[prost(float, tag = "2")]
pub x: f32,
#[prost(float, tag = "3")]
pub y: f32,
#[prost(float, tag = "4")]
pub z: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct EulerAngle {
#[prost(float, tag = "1")]
pub roll_deg: f32,
#[prost(float, tag = "2")]
pub pitch_deg: f32,
#[prost(float, tag = "3")]
pub yaw_deg: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AngularVelocityBody {
#[prost(float, tag = "1")]
pub roll_rad_s: f32,
#[prost(float, tag = "2")]
pub pitch_rad_s: f32,
#[prost(float, tag = "3")]
pub yaw_rad_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GpsInfo {
#[prost(int32, tag = "1")]
pub num_satellites: i32,
#[prost(enumeration = "FixType", tag = "2")]
pub fix_type: i32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Battery {
#[prost(float, tag = "1")]
pub voltage_v: f32,
#[prost(float, tag = "2")]
pub remaining_percent: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Health {
#[prost(bool, tag = "1")]
pub is_gyrometer_calibration_ok: bool,
#[prost(bool, tag = "2")]
pub is_accelerometer_calibration_ok: bool,
#[prost(bool, tag = "3")]
pub is_magnetometer_calibration_ok: bool,
#[prost(bool, tag = "4")]
pub is_level_calibration_ok: bool,
#[prost(bool, tag = "5")]
pub is_local_position_ok: bool,
#[prost(bool, tag = "6")]
pub is_global_position_ok: bool,
#[prost(bool, tag = "7")]
pub is_home_position_ok: bool,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct RcStatus {
#[prost(bool, tag = "1")]
pub was_available_once: bool,
#[prost(bool, tag = "2")]
pub is_available: bool,
#[prost(float, tag = "3")]
pub signal_strength_percent: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct StatusText {
#[prost(enumeration = "StatusTextType", tag = "1")]
pub r#type: i32,
#[prost(string, tag = "2")]
pub text: ::prost::alloc::string::String,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ActuatorControlTarget {
#[prost(int32, tag = "1")]
pub group: i32,
#[prost(float, repeated, tag = "2")]
pub controls: ::prost::alloc::vec::Vec<f32>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct ActuatorOutputStatus {
#[prost(uint32, tag = "1")]
pub active: u32,
#[prost(float, repeated, tag = "2")]
pub actuator: ::prost::alloc::vec::Vec<f32>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Covariance {
#[prost(float, repeated, tag = "1")]
pub covariance_matrix: ::prost::alloc::vec::Vec<f32>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct VelocityBody {
#[prost(float, tag = "1")]
pub x_m_s: f32,
#[prost(float, tag = "2")]
pub y_m_s: f32,
#[prost(float, tag = "3")]
pub z_m_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionBody {
#[prost(float, tag = "1")]
pub x_m: f32,
#[prost(float, tag = "2")]
pub y_m: f32,
#[prost(float, tag = "3")]
pub z_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Odometry {
#[prost(uint64, tag = "1")]
pub time_usec: u64,
#[prost(enumeration = "odometry::MavFrame", tag = "2")]
pub frame_id: i32,
#[prost(enumeration = "odometry::MavFrame", tag = "3")]
pub child_frame_id: i32,
#[prost(message, optional, tag = "4")]
pub position_body: ::core::option::Option<PositionBody>,
#[prost(message, optional, tag = "5")]
pub q: ::core::option::Option<Quaternion>,
#[prost(message, optional, tag = "6")]
pub velocity_body: ::core::option::Option<VelocityBody>,
#[prost(message, optional, tag = "7")]
pub angular_velocity_body: ::core::option::Option<AngularVelocityBody>,
#[prost(message, optional, tag = "8")]
pub pose_covariance: ::core::option::Option<Covariance>,
#[prost(message, optional, tag = "9")]
pub velocity_covariance: ::core::option::Option<Covariance>,
}
pub mod odometry {
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum MavFrame {
Undef = 0,
BodyNed = 8,
VisionNed = 16,
EstimNed = 18,
}
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct DistanceSensor {
#[prost(float, tag = "1")]
pub minimum_distance_m: f32,
#[prost(float, tag = "2")]
pub maximum_distance_m: f32,
#[prost(float, tag = "3")]
pub current_distance_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionNed {
#[prost(float, tag = "1")]
pub north_m: f32,
#[prost(float, tag = "2")]
pub east_m: f32,
#[prost(float, tag = "3")]
pub down_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct VelocityNed {
#[prost(float, tag = "1")]
pub north_m_s: f32,
#[prost(float, tag = "2")]
pub east_m_s: f32,
#[prost(float, tag = "3")]
pub down_m_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionVelocityNed {
#[prost(message, optional, tag = "1")]
pub position: ::core::option::Option<PositionNed>,
#[prost(message, optional, tag = "2")]
pub velocity: ::core::option::Option<VelocityNed>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GroundTruth {
#[prost(double, tag = "1")]
pub latitude_deg: f64,
#[prost(double, tag = "2")]
pub longitude_deg: f64,
#[prost(float, tag = "3")]
pub absolute_altitude_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct FixedwingMetrics {
#[prost(float, tag = "1")]
pub airspeed_m_s: f32,
#[prost(float, tag = "2")]
pub throttle_percentage: f32,
#[prost(float, tag = "3")]
pub climb_rate_m_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AccelerationFrd {
#[prost(float, tag = "1")]
pub forward_m_s2: f32,
#[prost(float, tag = "2")]
pub right_m_s2: f32,
#[prost(float, tag = "3")]
pub down_m_s2: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AngularVelocityFrd {
#[prost(float, tag = "1")]
pub forward_rad_s: f32,
#[prost(float, tag = "2")]
pub right_rad_s: f32,
#[prost(float, tag = "3")]
pub down_rad_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct MagneticFieldFrd {
#[prost(float, tag = "1")]
pub forward_gauss: f32,
#[prost(float, tag = "2")]
pub right_gauss: f32,
#[prost(float, tag = "3")]
pub down_gauss: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Imu {
#[prost(message, optional, tag = "1")]
pub acceleration_frd: ::core::option::Option<AccelerationFrd>,
#[prost(message, optional, tag = "2")]
pub angular_velocity_frd: ::core::option::Option<AngularVelocityFrd>,
#[prost(message, optional, tag = "3")]
pub magnetic_field_frd: ::core::option::Option<MagneticFieldFrd>,
#[prost(float, tag = "4")]
pub temperature_degc: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct GpsGlobalOrigin {
#[prost(double, tag = "1")]
pub latitude_deg: f64,
#[prost(double, tag = "2")]
pub longitude_deg: f64,
#[prost(float, tag = "3")]
pub altitude_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct TelemetryResult {
#[prost(enumeration = "telemetry_result::Result", tag = "1")]
pub result: i32,
#[prost(string, tag = "2")]
pub result_str: ::prost::alloc::string::String,
}
pub mod telemetry_result {
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum Result {
Unknown = 0,
Success = 1,
NoSystem = 2,
ConnectionError = 3,
Busy = 4,
CommandDenied = 5,
Timeout = 6,
}
}
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum FixType {
NoGps = 0,
NoFix = 1,
Fix2d = 2,
Fix3d = 3,
FixDgps = 4,
RtkFloat = 5,
RtkFixed = 6,
}
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum FlightMode {
Unknown = 0,
Ready = 1,
Takeoff = 2,
Hold = 3,
Mission = 4,
ReturnToLaunch = 5,
Land = 6,
Offboard = 7,
FollowMe = 8,
Manual = 9,
Altctl = 10,
Posctl = 11,
Acro = 12,
Stabilized = 13,
Rattitude = 14,
}
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum StatusTextType {
Debug = 0,
Info = 1,
Notice = 2,
Warning = 3,
Error = 4,
Critical = 5,
Alert = 6,
Emergency = 7,
}
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum LandedState {
Unknown = 0,
OnGround = 1,
InAir = 2,
TakingOff = 3,
Landing = 4,
}
#[doc = r" Generated client implementations."]
pub mod telemetry_service_client {
#![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
use tonic::codegen::*;
#[doc = ""]
#[doc = " Allow users to get vehicle telemetry and state information"]
#[doc = " (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates."]
#[derive(Debug, Clone)]
pub struct TelemetryServiceClient<T> {
inner: tonic::client::Grpc<T>,
}
impl TelemetryServiceClient<tonic::transport::Channel> {
#[doc = r" Attempt to create a new client by connecting to a given endpoint."]
pub async fn connect<D>(dst: D) -> Result<Self, tonic::transport::Error>
where
D: std::convert::TryInto<tonic::transport::Endpoint>,
D::Error: Into<StdError>,
{
let conn = tonic::transport::Endpoint::new(dst)?.connect().await?;
Ok(Self::new(conn))
}
}
impl<T> TelemetryServiceClient<T>
where
T: tonic::client::GrpcService<tonic::body::BoxBody>,
T::ResponseBody: Body + Send + Sync + 'static,
T::Error: Into<StdError>,
<T::ResponseBody as Body>::Error: Into<StdError> + Send,
{
pub fn new(inner: T) -> Self {
let inner = tonic::client::Grpc::new(inner);
Self { inner }
}
pub fn with_interceptor<F>(
inner: T,
interceptor: F,
) -> TelemetryServiceClient<InterceptedService<T, F>>
where
F: tonic::service::Interceptor,
T: tonic::codegen::Service<
http::Request<tonic::body::BoxBody>,
Response = http::Response<
<T as tonic::client::GrpcService<tonic::body::BoxBody>>::ResponseBody,
>,
>,
<T as tonic::codegen::Service<http::Request<tonic::body::BoxBody>>>::Error:
Into<StdError> + Send + Sync,
{
TelemetryServiceClient::new(InterceptedService::new(inner, interceptor))
}
#[doc = r" Compress requests with `gzip`."]
#[doc = r""]
#[doc = r" This requires the server to support it otherwise it might respond with an"]
#[doc = r" error."]
pub fn send_gzip(mut self) -> Self {
self.inner = self.inner.send_gzip();
self
}
#[doc = r" Enable decompressing responses with `gzip`."]
pub fn accept_gzip(mut self) -> Self {
self.inner = self.inner.accept_gzip();
self
}
#[doc = " Subscribe to 'position' updates."]
pub async fn subscribe_position(
&mut self,
request: impl tonic::IntoRequest<super::SubscribePositionRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::PositionResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'home position' updates."]
pub async fn subscribe_home(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeHomeRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::HomeResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to in-air updates."]
pub async fn subscribe_in_air(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeInAirRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::InAirResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to landed state updates"]
pub async fn subscribe_landed_state(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeLandedStateRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::LandedStateResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to armed updates."]
pub async fn subscribe_armed(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeArmedRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::ArmedResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'attitude' updates (quaternion)."]
pub async fn subscribe_attitude_quaternion(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeAttitudeQuaternionRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::AttitudeQuaternionResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'attitude' updates (Euler)."]
pub async fn subscribe_attitude_euler(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeAttitudeEulerRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::AttitudeEulerResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'attitude' updates (angular velocity)"]
pub async fn subscribe_attitude_angular_velocity_body(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeAttitudeAngularVelocityBodyRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::AttitudeAngularVelocityBodyResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'camera attitude' updates (quaternion)."]
pub async fn subscribe_camera_attitude_quaternion(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeCameraAttitudeQuaternionRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::CameraAttitudeQuaternionResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'camera attitude' updates (Euler)."]
pub async fn subscribe_camera_attitude_euler(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeCameraAttitudeEulerRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::CameraAttitudeEulerResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeEuler",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'ground speed' updates (NED)."]
pub async fn subscribe_velocity_ned(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeVelocityNedRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::VelocityNedResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'GPS info' updates."]
pub async fn subscribe_gps_info(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeGpsInfoRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::GpsInfoResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'battery' updates."]
pub async fn subscribe_battery(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeBatteryRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::BatteryResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'flight mode' updates."]
pub async fn subscribe_flight_mode(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeFlightModeRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::FlightModeResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'health' updates."]
pub async fn subscribe_health(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeHealthRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::HealthResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'RC status' updates."]
pub async fn subscribe_rc_status(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeRcStatusRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::RcStatusResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'status text' updates."]
pub async fn subscribe_status_text(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeStatusTextRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::StatusTextResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'actuator control target' updates."]
pub async fn subscribe_actuator_control_target(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeActuatorControlTargetRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::ActuatorControlTargetResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'actuator output status' updates."]
pub async fn subscribe_actuator_output_status(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeActuatorOutputStatusRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::ActuatorOutputStatusResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'odometry' updates."]
pub async fn subscribe_odometry(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeOdometryRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::OdometryResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'position velocity' updates."]
pub async fn subscribe_position_velocity_ned(
&mut self,
request: impl tonic::IntoRequest<super::SubscribePositionVelocityNedRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::PositionVelocityNedResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'ground truth' updates."]
pub async fn subscribe_ground_truth(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeGroundTruthRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::GroundTruthResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'fixedwing metrics' updates."]
pub async fn subscribe_fixedwing_metrics(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeFixedwingMetricsRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::FixedwingMetricsResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'IMU' updates."]
pub async fn subscribe_imu(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeImuRequest>,
) -> Result<tonic::Response<tonic::codec::Streaming<super::ImuResponse>>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'HealthAllOk' updates."]
pub async fn subscribe_health_all_ok(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeHealthAllOkRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::HealthAllOkResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'unix epoch time' updates."]
pub async fn subscribe_unix_epoch_time(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeUnixEpochTimeRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::UnixEpochTimeResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Subscribe to 'Distance Sensor' updates."]
pub async fn subscribe_distance_sensor(
&mut self,
request: impl tonic::IntoRequest<super::SubscribeDistanceSensorRequest>,
) -> Result<
tonic::Response<tonic::codec::Streaming<super::DistanceSensorResponse>>,
tonic::Status,
> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor",
);
self.inner
.server_streaming(request.into_request(), path, codec)
.await
}
#[doc = " Set rate to 'position' updates."]
pub async fn set_rate_position(
&mut self,
request: impl tonic::IntoRequest<super::SetRatePositionRequest>,
) -> Result<tonic::Response<super::SetRatePositionResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'home position' updates."]
pub async fn set_rate_home(
&mut self,
request: impl tonic::IntoRequest<super::SetRateHomeRequest>,
) -> Result<tonic::Response<super::SetRateHomeResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateHome",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to in-air updates."]
pub async fn set_rate_in_air(
&mut self,
request: impl tonic::IntoRequest<super::SetRateInAirRequest>,
) -> Result<tonic::Response<super::SetRateInAirResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to landed state updates"]
pub async fn set_rate_landed_state(
&mut self,
request: impl tonic::IntoRequest<super::SetRateLandedStateRequest>,
) -> Result<tonic::Response<super::SetRateLandedStateResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'attitude' updates."]
pub async fn set_rate_attitude(
&mut self,
request: impl tonic::IntoRequest<super::SetRateAttitudeRequest>,
) -> Result<tonic::Response<super::SetRateAttitudeResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitude",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate of camera attitude updates."]
pub async fn set_rate_camera_attitude(
&mut self,
request: impl tonic::IntoRequest<super::SetRateCameraAttitudeRequest>,
) -> Result<tonic::Response<super::SetRateCameraAttitudeResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateCameraAttitude",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'ground speed' updates (NED)."]
pub async fn set_rate_velocity_ned(
&mut self,
request: impl tonic::IntoRequest<super::SetRateVelocityNedRequest>,
) -> Result<tonic::Response<super::SetRateVelocityNedResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'GPS info' updates."]
pub async fn set_rate_gps_info(
&mut self,
request: impl tonic::IntoRequest<super::SetRateGpsInfoRequest>,
) -> Result<tonic::Response<super::SetRateGpsInfoResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'battery' updates."]
pub async fn set_rate_battery(
&mut self,
request: impl tonic::IntoRequest<super::SetRateBatteryRequest>,
) -> Result<tonic::Response<super::SetRateBatteryResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'RC status' updates."]
pub async fn set_rate_rc_status(
&mut self,
request: impl tonic::IntoRequest<super::SetRateRcStatusRequest>,
) -> Result<tonic::Response<super::SetRateRcStatusResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'actuator control target' updates."]
pub async fn set_rate_actuator_control_target(
&mut self,
request: impl tonic::IntoRequest<super::SetRateActuatorControlTargetRequest>,
) -> Result<tonic::Response<super::SetRateActuatorControlTargetResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'actuator output status' updates."]
pub async fn set_rate_actuator_output_status(
&mut self,
request: impl tonic::IntoRequest<super::SetRateActuatorOutputStatusRequest>,
) -> Result<tonic::Response<super::SetRateActuatorOutputStatusResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'odometry' updates."]
pub async fn set_rate_odometry(
&mut self,
request: impl tonic::IntoRequest<super::SetRateOdometryRequest>,
) -> Result<tonic::Response<super::SetRateOdometryResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'position velocity' updates."]
pub async fn set_rate_position_velocity_ned(
&mut self,
request: impl tonic::IntoRequest<super::SetRatePositionVelocityNedRequest>,
) -> Result<tonic::Response<super::SetRatePositionVelocityNedResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'ground truth' updates."]
pub async fn set_rate_ground_truth(
&mut self,
request: impl tonic::IntoRequest<super::SetRateGroundTruthRequest>,
) -> Result<tonic::Response<super::SetRateGroundTruthResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'fixedwing metrics' updates."]
pub async fn set_rate_fixedwing_metrics(
&mut self,
request: impl tonic::IntoRequest<super::SetRateFixedwingMetricsRequest>,
) -> Result<tonic::Response<super::SetRateFixedwingMetricsResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'IMU' updates."]
pub async fn set_rate_imu(
&mut self,
request: impl tonic::IntoRequest<super::SetRateImuRequest>,
) -> Result<tonic::Response<super::SetRateImuResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateImu",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'unix epoch time' updates."]
pub async fn set_rate_unix_epoch_time(
&mut self,
request: impl tonic::IntoRequest<super::SetRateUnixEpochTimeRequest>,
) -> Result<tonic::Response<super::SetRateUnixEpochTimeResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Set rate to 'Distance Sensor' updates."]
pub async fn set_rate_distance_sensor(
&mut self,
request: impl tonic::IntoRequest<super::SetRateDistanceSensorRequest>,
) -> Result<tonic::Response<super::SetRateDistanceSensorResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Get the GPS location of where the estimator has been initialized."]
pub async fn get_gps_global_origin(
&mut self,
request: impl tonic::IntoRequest<super::GetGpsGlobalOriginRequest>,
) -> Result<tonic::Response<super::GetGpsGlobalOriginResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin",
);
self.inner.unary(request.into_request(), path, codec).await
}
}
}
#[doc = r" Generated server implementations."]
pub mod telemetry_service_server {
#![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
use tonic::codegen::*;
#[doc = "Generated trait containing gRPC methods that should be implemented for use with TelemetryServiceServer."]
#[async_trait]
pub trait TelemetryService: Send + Sync + 'static {
#[doc = "Server streaming response type for the SubscribePosition method."]
type SubscribePositionStream: futures_core::Stream<Item = Result<super::PositionResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'position' updates."]
async fn subscribe_position(
&self,
request: tonic::Request<super::SubscribePositionRequest>,
) -> Result<tonic::Response<Self::SubscribePositionStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeHome method."]
type SubscribeHomeStream: futures_core::Stream<Item = Result<super::HomeResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'home position' updates."]
async fn subscribe_home(
&self,
request: tonic::Request<super::SubscribeHomeRequest>,
) -> Result<tonic::Response<Self::SubscribeHomeStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeInAir method."]
type SubscribeInAirStream: futures_core::Stream<Item = Result<super::InAirResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to in-air updates."]
async fn subscribe_in_air(
&self,
request: tonic::Request<super::SubscribeInAirRequest>,
) -> Result<tonic::Response<Self::SubscribeInAirStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeLandedState method."]
type SubscribeLandedStateStream: futures_core::Stream<Item = Result<super::LandedStateResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to landed state updates"]
async fn subscribe_landed_state(
&self,
request: tonic::Request<super::SubscribeLandedStateRequest>,
) -> Result<tonic::Response<Self::SubscribeLandedStateStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeArmed method."]
type SubscribeArmedStream: futures_core::Stream<Item = Result<super::ArmedResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to armed updates."]
async fn subscribe_armed(
&self,
request: tonic::Request<super::SubscribeArmedRequest>,
) -> Result<tonic::Response<Self::SubscribeArmedStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeAttitudeQuaternion method."]
type SubscribeAttitudeQuaternionStream: futures_core::Stream<Item = Result<super::AttitudeQuaternionResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'attitude' updates (quaternion)."]
async fn subscribe_attitude_quaternion(
&self,
request: tonic::Request<super::SubscribeAttitudeQuaternionRequest>,
) -> Result<tonic::Response<Self::SubscribeAttitudeQuaternionStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeAttitudeEuler method."]
type SubscribeAttitudeEulerStream: futures_core::Stream<Item = Result<super::AttitudeEulerResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'attitude' updates (Euler)."]
async fn subscribe_attitude_euler(
&self,
request: tonic::Request<super::SubscribeAttitudeEulerRequest>,
) -> Result<tonic::Response<Self::SubscribeAttitudeEulerStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeAttitudeAngularVelocityBody method."]
type SubscribeAttitudeAngularVelocityBodyStream: futures_core::Stream<
Item = Result<super::AttitudeAngularVelocityBodyResponse, tonic::Status>,
> + Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'attitude' updates (angular velocity)"]
async fn subscribe_attitude_angular_velocity_body(
&self,
request: tonic::Request<super::SubscribeAttitudeAngularVelocityBodyRequest>,
) -> Result<tonic::Response<Self::SubscribeAttitudeAngularVelocityBodyStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeCameraAttitudeQuaternion method."]
type SubscribeCameraAttitudeQuaternionStream: futures_core::Stream<
Item = Result<super::CameraAttitudeQuaternionResponse, tonic::Status>,
> + Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'camera attitude' updates (quaternion)."]
async fn subscribe_camera_attitude_quaternion(
&self,
request: tonic::Request<super::SubscribeCameraAttitudeQuaternionRequest>,
) -> Result<tonic::Response<Self::SubscribeCameraAttitudeQuaternionStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeCameraAttitudeEuler method."]
type SubscribeCameraAttitudeEulerStream: futures_core::Stream<Item = Result<super::CameraAttitudeEulerResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'camera attitude' updates (Euler)."]
async fn subscribe_camera_attitude_euler(
&self,
request: tonic::Request<super::SubscribeCameraAttitudeEulerRequest>,
) -> Result<tonic::Response<Self::SubscribeCameraAttitudeEulerStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeVelocityNed method."]
type SubscribeVelocityNedStream: futures_core::Stream<Item = Result<super::VelocityNedResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'ground speed' updates (NED)."]
async fn subscribe_velocity_ned(
&self,
request: tonic::Request<super::SubscribeVelocityNedRequest>,
) -> Result<tonic::Response<Self::SubscribeVelocityNedStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeGpsInfo method."]
type SubscribeGpsInfoStream: futures_core::Stream<Item = Result<super::GpsInfoResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'GPS info' updates."]
async fn subscribe_gps_info(
&self,
request: tonic::Request<super::SubscribeGpsInfoRequest>,
) -> Result<tonic::Response<Self::SubscribeGpsInfoStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeBattery method."]
type SubscribeBatteryStream: futures_core::Stream<Item = Result<super::BatteryResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'battery' updates."]
async fn subscribe_battery(
&self,
request: tonic::Request<super::SubscribeBatteryRequest>,
) -> Result<tonic::Response<Self::SubscribeBatteryStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeFlightMode method."]
type SubscribeFlightModeStream: futures_core::Stream<Item = Result<super::FlightModeResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'flight mode' updates."]
async fn subscribe_flight_mode(
&self,
request: tonic::Request<super::SubscribeFlightModeRequest>,
) -> Result<tonic::Response<Self::SubscribeFlightModeStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeHealth method."]
type SubscribeHealthStream: futures_core::Stream<Item = Result<super::HealthResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'health' updates."]
async fn subscribe_health(
&self,
request: tonic::Request<super::SubscribeHealthRequest>,
) -> Result<tonic::Response<Self::SubscribeHealthStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeRcStatus method."]
type SubscribeRcStatusStream: futures_core::Stream<Item = Result<super::RcStatusResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'RC status' updates."]
async fn subscribe_rc_status(
&self,
request: tonic::Request<super::SubscribeRcStatusRequest>,
) -> Result<tonic::Response<Self::SubscribeRcStatusStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeStatusText method."]
type SubscribeStatusTextStream: futures_core::Stream<Item = Result<super::StatusTextResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'status text' updates."]
async fn subscribe_status_text(
&self,
request: tonic::Request<super::SubscribeStatusTextRequest>,
) -> Result<tonic::Response<Self::SubscribeStatusTextStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeActuatorControlTarget method."]
type SubscribeActuatorControlTargetStream: futures_core::Stream<Item = Result<super::ActuatorControlTargetResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'actuator control target' updates."]
async fn subscribe_actuator_control_target(
&self,
request: tonic::Request<super::SubscribeActuatorControlTargetRequest>,
) -> Result<tonic::Response<Self::SubscribeActuatorControlTargetStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeActuatorOutputStatus method."]
type SubscribeActuatorOutputStatusStream: futures_core::Stream<Item = Result<super::ActuatorOutputStatusResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'actuator output status' updates."]
async fn subscribe_actuator_output_status(
&self,
request: tonic::Request<super::SubscribeActuatorOutputStatusRequest>,
) -> Result<tonic::Response<Self::SubscribeActuatorOutputStatusStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeOdometry method."]
type SubscribeOdometryStream: futures_core::Stream<Item = Result<super::OdometryResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'odometry' updates."]
async fn subscribe_odometry(
&self,
request: tonic::Request<super::SubscribeOdometryRequest>,
) -> Result<tonic::Response<Self::SubscribeOdometryStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribePositionVelocityNed method."]
type SubscribePositionVelocityNedStream: futures_core::Stream<Item = Result<super::PositionVelocityNedResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'position velocity' updates."]
async fn subscribe_position_velocity_ned(
&self,
request: tonic::Request<super::SubscribePositionVelocityNedRequest>,
) -> Result<tonic::Response<Self::SubscribePositionVelocityNedStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeGroundTruth method."]
type SubscribeGroundTruthStream: futures_core::Stream<Item = Result<super::GroundTruthResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'ground truth' updates."]
async fn subscribe_ground_truth(
&self,
request: tonic::Request<super::SubscribeGroundTruthRequest>,
) -> Result<tonic::Response<Self::SubscribeGroundTruthStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeFixedwingMetrics method."]
type SubscribeFixedwingMetricsStream: futures_core::Stream<Item = Result<super::FixedwingMetricsResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'fixedwing metrics' updates."]
async fn subscribe_fixedwing_metrics(
&self,
request: tonic::Request<super::SubscribeFixedwingMetricsRequest>,
) -> Result<tonic::Response<Self::SubscribeFixedwingMetricsStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeImu method."]
type SubscribeImuStream: futures_core::Stream<Item = Result<super::ImuResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'IMU' updates."]
async fn subscribe_imu(
&self,
request: tonic::Request<super::SubscribeImuRequest>,
) -> Result<tonic::Response<Self::SubscribeImuStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeHealthAllOk method."]
type SubscribeHealthAllOkStream: futures_core::Stream<Item = Result<super::HealthAllOkResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'HealthAllOk' updates."]
async fn subscribe_health_all_ok(
&self,
request: tonic::Request<super::SubscribeHealthAllOkRequest>,
) -> Result<tonic::Response<Self::SubscribeHealthAllOkStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeUnixEpochTime method."]
type SubscribeUnixEpochTimeStream: futures_core::Stream<Item = Result<super::UnixEpochTimeResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'unix epoch time' updates."]
async fn subscribe_unix_epoch_time(
&self,
request: tonic::Request<super::SubscribeUnixEpochTimeRequest>,
) -> Result<tonic::Response<Self::SubscribeUnixEpochTimeStream>, tonic::Status>;
#[doc = "Server streaming response type for the SubscribeDistanceSensor method."]
type SubscribeDistanceSensorStream: futures_core::Stream<Item = Result<super::DistanceSensorResponse, tonic::Status>>
+ Send
+ Sync
+ 'static;
#[doc = " Subscribe to 'Distance Sensor' updates."]
async fn subscribe_distance_sensor(
&self,
request: tonic::Request<super::SubscribeDistanceSensorRequest>,
) -> Result<tonic::Response<Self::SubscribeDistanceSensorStream>, tonic::Status>;
#[doc = " Set rate to 'position' updates."]
async fn set_rate_position(
&self,
request: tonic::Request<super::SetRatePositionRequest>,
) -> Result<tonic::Response<super::SetRatePositionResponse>, tonic::Status>;
#[doc = " Set rate to 'home position' updates."]
async fn set_rate_home(
&self,
request: tonic::Request<super::SetRateHomeRequest>,
) -> Result<tonic::Response<super::SetRateHomeResponse>, tonic::Status>;
#[doc = " Set rate to in-air updates."]
async fn set_rate_in_air(
&self,
request: tonic::Request<super::SetRateInAirRequest>,
) -> Result<tonic::Response<super::SetRateInAirResponse>, tonic::Status>;
#[doc = " Set rate to landed state updates"]
async fn set_rate_landed_state(
&self,
request: tonic::Request<super::SetRateLandedStateRequest>,
) -> Result<tonic::Response<super::SetRateLandedStateResponse>, tonic::Status>;
#[doc = " Set rate to 'attitude' updates."]
async fn set_rate_attitude(
&self,
request: tonic::Request<super::SetRateAttitudeRequest>,
) -> Result<tonic::Response<super::SetRateAttitudeResponse>, tonic::Status>;
#[doc = " Set rate of camera attitude updates."]
async fn set_rate_camera_attitude(
&self,
request: tonic::Request<super::SetRateCameraAttitudeRequest>,
) -> Result<tonic::Response<super::SetRateCameraAttitudeResponse>, tonic::Status>;
#[doc = " Set rate to 'ground speed' updates (NED)."]
async fn set_rate_velocity_ned(
&self,
request: tonic::Request<super::SetRateVelocityNedRequest>,
) -> Result<tonic::Response<super::SetRateVelocityNedResponse>, tonic::Status>;
#[doc = " Set rate to 'GPS info' updates."]
async fn set_rate_gps_info(
&self,
request: tonic::Request<super::SetRateGpsInfoRequest>,
) -> Result<tonic::Response<super::SetRateGpsInfoResponse>, tonic::Status>;
#[doc = " Set rate to 'battery' updates."]
async fn set_rate_battery(
&self,
request: tonic::Request<super::SetRateBatteryRequest>,
) -> Result<tonic::Response<super::SetRateBatteryResponse>, tonic::Status>;
#[doc = " Set rate to 'RC status' updates."]
async fn set_rate_rc_status(
&self,
request: tonic::Request<super::SetRateRcStatusRequest>,
) -> Result<tonic::Response<super::SetRateRcStatusResponse>, tonic::Status>;
#[doc = " Set rate to 'actuator control target' updates."]
async fn set_rate_actuator_control_target(
&self,
request: tonic::Request<super::SetRateActuatorControlTargetRequest>,
) -> Result<tonic::Response<super::SetRateActuatorControlTargetResponse>, tonic::Status>;
#[doc = " Set rate to 'actuator output status' updates."]
async fn set_rate_actuator_output_status(
&self,
request: tonic::Request<super::SetRateActuatorOutputStatusRequest>,
) -> Result<tonic::Response<super::SetRateActuatorOutputStatusResponse>, tonic::Status>;
#[doc = " Set rate to 'odometry' updates."]
async fn set_rate_odometry(
&self,
request: tonic::Request<super::SetRateOdometryRequest>,
) -> Result<tonic::Response<super::SetRateOdometryResponse>, tonic::Status>;
#[doc = " Set rate to 'position velocity' updates."]
async fn set_rate_position_velocity_ned(
&self,
request: tonic::Request<super::SetRatePositionVelocityNedRequest>,
) -> Result<tonic::Response<super::SetRatePositionVelocityNedResponse>, tonic::Status>;
#[doc = " Set rate to 'ground truth' updates."]
async fn set_rate_ground_truth(
&self,
request: tonic::Request<super::SetRateGroundTruthRequest>,
) -> Result<tonic::Response<super::SetRateGroundTruthResponse>, tonic::Status>;
#[doc = " Set rate to 'fixedwing metrics' updates."]
async fn set_rate_fixedwing_metrics(
&self,
request: tonic::Request<super::SetRateFixedwingMetricsRequest>,
) -> Result<tonic::Response<super::SetRateFixedwingMetricsResponse>, tonic::Status>;
#[doc = " Set rate to 'IMU' updates."]
async fn set_rate_imu(
&self,
request: tonic::Request<super::SetRateImuRequest>,
) -> Result<tonic::Response<super::SetRateImuResponse>, tonic::Status>;
#[doc = " Set rate to 'unix epoch time' updates."]
async fn set_rate_unix_epoch_time(
&self,
request: tonic::Request<super::SetRateUnixEpochTimeRequest>,
) -> Result<tonic::Response<super::SetRateUnixEpochTimeResponse>, tonic::Status>;
#[doc = " Set rate to 'Distance Sensor' updates."]
async fn set_rate_distance_sensor(
&self,
request: tonic::Request<super::SetRateDistanceSensorRequest>,
) -> Result<tonic::Response<super::SetRateDistanceSensorResponse>, tonic::Status>;
#[doc = " Get the GPS location of where the estimator has been initialized."]
async fn get_gps_global_origin(
&self,
request: tonic::Request<super::GetGpsGlobalOriginRequest>,
) -> Result<tonic::Response<super::GetGpsGlobalOriginResponse>, tonic::Status>;
}
#[doc = ""]
#[doc = " Allow users to get vehicle telemetry and state information"]
#[doc = " (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates."]
#[derive(Debug)]
pub struct TelemetryServiceServer<T: TelemetryService> {
inner: _Inner<T>,
accept_compression_encodings: (),
send_compression_encodings: (),
}
struct _Inner<T>(Arc<T>);
impl<T: TelemetryService> TelemetryServiceServer<T> {
pub fn new(inner: T) -> Self {
let inner = Arc::new(inner);
let inner = _Inner(inner);
Self {
inner,
accept_compression_encodings: Default::default(),
send_compression_encodings: Default::default(),
}
}
pub fn with_interceptor<F>(inner: T, interceptor: F) -> InterceptedService<Self, F>
where
F: tonic::service::Interceptor,
{
InterceptedService::new(Self::new(inner), interceptor)
}
}
impl<T, B> tonic::codegen::Service<http::Request<B>> for TelemetryServiceServer<T>
where
T: TelemetryService,
B: Body + Send + Sync + 'static,
B::Error: Into<StdError> + Send + 'static,
{
type Response = http::Response<tonic::body::BoxBody>;
type Error = Never;
type Future = BoxFuture<Self::Response, Self::Error>;
fn poll_ready(&mut self, _cx: &mut Context<'_>) -> Poll<Result<(), Self::Error>> {
Poll::Ready(Ok(()))
}
fn call(&mut self, req: http::Request<B>) -> Self::Future {
let inner = self.inner.clone();
match req.uri().path() {
"/mavsdk.rpc.telemetry.TelemetryService/SubscribePosition" => {
#[allow(non_camel_case_types)]
struct SubscribePositionSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribePositionRequest>
for SubscribePositionSvc<T>
{
type Response = super::PositionResponse;
type ResponseStream = T::SubscribePositionStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribePositionRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_position(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribePositionSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHome" => {
#[allow(non_camel_case_types)]
struct SubscribeHomeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeHomeRequest>
for SubscribeHomeSvc<T>
{
type Response = super::HomeResponse;
type ResponseStream = T::SubscribeHomeStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeHomeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_home(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeHomeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeInAir" => {
#[allow(non_camel_case_types)]
struct SubscribeInAirSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeInAirRequest>
for SubscribeInAirSvc<T>
{
type Response = super::InAirResponse;
type ResponseStream = T::SubscribeInAirStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeInAirRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_in_air(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeInAirSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeLandedState" => {
#[allow(non_camel_case_types)]
struct SubscribeLandedStateSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeLandedStateRequest>
for SubscribeLandedStateSvc<T>
{
type Response = super::LandedStateResponse;
type ResponseStream = T::SubscribeLandedStateStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeLandedStateRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_landed_state(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeLandedStateSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed" => {
#[allow(non_camel_case_types)]
struct SubscribeArmedSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeArmedRequest>
for SubscribeArmedSvc<T>
{
type Response = super::ArmedResponse;
type ResponseStream = T::SubscribeArmedStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeArmedRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_armed(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeArmedSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion" => {
#[allow(non_camel_case_types)]
struct SubscribeAttitudeQuaternionSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeAttitudeQuaternionRequest,
> for SubscribeAttitudeQuaternionSvc<T>
{
type Response = super::AttitudeQuaternionResponse;
type ResponseStream = T::SubscribeAttitudeQuaternionStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeAttitudeQuaternionRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_attitude_quaternion(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeAttitudeQuaternionSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler" => {
#[allow(non_camel_case_types)]
struct SubscribeAttitudeEulerSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeAttitudeEulerRequest>
for SubscribeAttitudeEulerSvc<T>
{
type Response = super::AttitudeEulerResponse;
type ResponseStream = T::SubscribeAttitudeEulerStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeAttitudeEulerRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).subscribe_attitude_euler(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeAttitudeEulerSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody" => {
#[allow(non_camel_case_types)]
struct SubscribeAttitudeAngularVelocityBodySvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeAttitudeAngularVelocityBodyRequest,
> for SubscribeAttitudeAngularVelocityBodySvc<T>
{
type Response = super::AttitudeAngularVelocityBodyResponse;
type ResponseStream = T::SubscribeAttitudeAngularVelocityBodyStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<
super::SubscribeAttitudeAngularVelocityBodyRequest,
>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner)
.subscribe_attitude_angular_velocity_body(request)
.await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeAttitudeAngularVelocityBodySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion" => {
#[allow(non_camel_case_types)]
struct SubscribeCameraAttitudeQuaternionSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeCameraAttitudeQuaternionRequest,
> for SubscribeCameraAttitudeQuaternionSvc<T>
{
type Response = super::CameraAttitudeQuaternionResponse;
type ResponseStream = T::SubscribeCameraAttitudeQuaternionStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<
super::SubscribeCameraAttitudeQuaternionRequest,
>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_camera_attitude_quaternion(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeCameraAttitudeQuaternionSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeEuler" => {
#[allow(non_camel_case_types)]
struct SubscribeCameraAttitudeEulerSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeCameraAttitudeEulerRequest,
> for SubscribeCameraAttitudeEulerSvc<T>
{
type Response = super::CameraAttitudeEulerResponse;
type ResponseStream = T::SubscribeCameraAttitudeEulerStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeCameraAttitudeEulerRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_camera_attitude_euler(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeCameraAttitudeEulerSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeVelocityNed" => {
#[allow(non_camel_case_types)]
struct SubscribeVelocityNedSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeVelocityNedRequest>
for SubscribeVelocityNedSvc<T>
{
type Response = super::VelocityNedResponse;
type ResponseStream = T::SubscribeVelocityNedStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeVelocityNedRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_velocity_ned(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeVelocityNedSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeGpsInfo" => {
#[allow(non_camel_case_types)]
struct SubscribeGpsInfoSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeGpsInfoRequest>
for SubscribeGpsInfoSvc<T>
{
type Response = super::GpsInfoResponse;
type ResponseStream = T::SubscribeGpsInfoStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeGpsInfoRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_gps_info(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeGpsInfoSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeBattery" => {
#[allow(non_camel_case_types)]
struct SubscribeBatterySvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeBatteryRequest>
for SubscribeBatterySvc<T>
{
type Response = super::BatteryResponse;
type ResponseStream = T::SubscribeBatteryStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeBatteryRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_battery(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeBatterySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeFlightMode" => {
#[allow(non_camel_case_types)]
struct SubscribeFlightModeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeFlightModeRequest>
for SubscribeFlightModeSvc<T>
{
type Response = super::FlightModeResponse;
type ResponseStream = T::SubscribeFlightModeStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeFlightModeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_flight_mode(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeFlightModeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth" => {
#[allow(non_camel_case_types)]
struct SubscribeHealthSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeHealthRequest>
for SubscribeHealthSvc<T>
{
type Response = super::HealthResponse;
type ResponseStream = T::SubscribeHealthStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeHealthRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_health(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeHealthSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus" => {
#[allow(non_camel_case_types)]
struct SubscribeRcStatusSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeRcStatusRequest>
for SubscribeRcStatusSvc<T>
{
type Response = super::RcStatusResponse;
type ResponseStream = T::SubscribeRcStatusStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeRcStatusRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_rc_status(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeRcStatusSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText" => {
#[allow(non_camel_case_types)]
struct SubscribeStatusTextSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeStatusTextRequest>
for SubscribeStatusTextSvc<T>
{
type Response = super::StatusTextResponse;
type ResponseStream = T::SubscribeStatusTextStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeStatusTextRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_status_text(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeStatusTextSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget" => {
#[allow(non_camel_case_types)]
struct SubscribeActuatorControlTargetSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeActuatorControlTargetRequest,
> for SubscribeActuatorControlTargetSvc<T>
{
type Response = super::ActuatorControlTargetResponse;
type ResponseStream = T::SubscribeActuatorControlTargetStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeActuatorControlTargetRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_actuator_control_target(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeActuatorControlTargetSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus" => {
#[allow(non_camel_case_types)]
struct SubscribeActuatorOutputStatusSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeActuatorOutputStatusRequest,
> for SubscribeActuatorOutputStatusSvc<T>
{
type Response = super::ActuatorOutputStatusResponse;
type ResponseStream = T::SubscribeActuatorOutputStatusStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeActuatorOutputStatusRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_actuator_output_status(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeActuatorOutputStatusSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeOdometry" => {
#[allow(non_camel_case_types)]
struct SubscribeOdometrySvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeOdometryRequest>
for SubscribeOdometrySvc<T>
{
type Response = super::OdometryResponse;
type ResponseStream = T::SubscribeOdometryStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeOdometryRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_odometry(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeOdometrySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribePositionVelocityNed" => {
#[allow(non_camel_case_types)]
struct SubscribePositionVelocityNedSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribePositionVelocityNedRequest,
> for SubscribePositionVelocityNedSvc<T>
{
type Response = super::PositionVelocityNedResponse;
type ResponseStream = T::SubscribePositionVelocityNedStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribePositionVelocityNedRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).subscribe_position_velocity_ned(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribePositionVelocityNedSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundTruth" => {
#[allow(non_camel_case_types)]
struct SubscribeGroundTruthSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeGroundTruthRequest>
for SubscribeGroundTruthSvc<T>
{
type Response = super::GroundTruthResponse;
type ResponseStream = T::SubscribeGroundTruthStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeGroundTruthRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_ground_truth(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeGroundTruthSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeFixedwingMetrics" => {
#[allow(non_camel_case_types)]
struct SubscribeFixedwingMetricsSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<
super::SubscribeFixedwingMetricsRequest,
> for SubscribeFixedwingMetricsSvc<T>
{
type Response = super::FixedwingMetricsResponse;
type ResponseStream = T::SubscribeFixedwingMetricsStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeFixedwingMetricsRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).subscribe_fixedwing_metrics(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeFixedwingMetricsSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeImu" => {
#[allow(non_camel_case_types)]
struct SubscribeImuSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeImuRequest>
for SubscribeImuSvc<T>
{
type Response = super::ImuResponse;
type ResponseStream = T::SubscribeImuStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeImuRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).subscribe_imu(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeImuSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealthAllOk" => {
#[allow(non_camel_case_types)]
struct SubscribeHealthAllOkSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeHealthAllOkRequest>
for SubscribeHealthAllOkSvc<T>
{
type Response = super::HealthAllOkResponse;
type ResponseStream = T::SubscribeHealthAllOkStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeHealthAllOkRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).subscribe_health_all_ok(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeHealthAllOkSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeUnixEpochTime" => {
#[allow(non_camel_case_types)]
struct SubscribeUnixEpochTimeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeUnixEpochTimeRequest>
for SubscribeUnixEpochTimeSvc<T>
{
type Response = super::UnixEpochTimeResponse;
type ResponseStream = T::SubscribeUnixEpochTimeStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeUnixEpochTimeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).subscribe_unix_epoch_time(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeUnixEpochTimeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SubscribeDistanceSensor" => {
#[allow(non_camel_case_types)]
struct SubscribeDistanceSensorSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::ServerStreamingService<super::SubscribeDistanceSensorRequest>
for SubscribeDistanceSensorSvc<T>
{
type Response = super::DistanceSensorResponse;
type ResponseStream = T::SubscribeDistanceSensorStream;
type Future =
BoxFuture<tonic::Response<Self::ResponseStream>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SubscribeDistanceSensorRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).subscribe_distance_sensor(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SubscribeDistanceSensorSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.server_streaming(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRatePosition" => {
#[allow(non_camel_case_types)]
struct SetRatePositionSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRatePositionRequest>
for SetRatePositionSvc<T>
{
type Response = super::SetRatePositionResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRatePositionRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_position(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRatePositionSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateHome" => {
#[allow(non_camel_case_types)]
struct SetRateHomeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService> tonic::server::UnaryService<super::SetRateHomeRequest>
for SetRateHomeSvc<T>
{
type Response = super::SetRateHomeResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateHomeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_home(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateHomeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateInAir" => {
#[allow(non_camel_case_types)]
struct SetRateInAirSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateInAirRequest>
for SetRateInAirSvc<T>
{
type Response = super::SetRateInAirResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateInAirRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_in_air(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateInAirSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateLandedState" => {
#[allow(non_camel_case_types)]
struct SetRateLandedStateSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateLandedStateRequest>
for SetRateLandedStateSvc<T>
{
type Response = super::SetRateLandedStateResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateLandedStateRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_landed_state(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateLandedStateSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateAttitude" => {
#[allow(non_camel_case_types)]
struct SetRateAttitudeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateAttitudeRequest>
for SetRateAttitudeSvc<T>
{
type Response = super::SetRateAttitudeResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateAttitudeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_attitude(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateAttitudeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateCameraAttitude" => {
#[allow(non_camel_case_types)]
struct SetRateCameraAttitudeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateCameraAttitudeRequest>
for SetRateCameraAttitudeSvc<T>
{
type Response = super::SetRateCameraAttitudeResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateCameraAttitudeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_rate_camera_attitude(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateCameraAttitudeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateVelocityNed" => {
#[allow(non_camel_case_types)]
struct SetRateVelocityNedSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateVelocityNedRequest>
for SetRateVelocityNedSvc<T>
{
type Response = super::SetRateVelocityNedResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateVelocityNedRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_velocity_ned(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateVelocityNedSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateGpsInfo" => {
#[allow(non_camel_case_types)]
struct SetRateGpsInfoSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateGpsInfoRequest>
for SetRateGpsInfoSvc<T>
{
type Response = super::SetRateGpsInfoResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateGpsInfoRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_gps_info(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateGpsInfoSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateBattery" => {
#[allow(non_camel_case_types)]
struct SetRateBatterySvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateBatteryRequest>
for SetRateBatterySvc<T>
{
type Response = super::SetRateBatteryResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateBatteryRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_battery(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateBatterySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateRcStatus" => {
#[allow(non_camel_case_types)]
struct SetRateRcStatusSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateRcStatusRequest>
for SetRateRcStatusSvc<T>
{
type Response = super::SetRateRcStatusResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateRcStatusRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_rc_status(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateRcStatusSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorControlTarget" => {
#[allow(non_camel_case_types)]
struct SetRateActuatorControlTargetSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateActuatorControlTargetRequest>
for SetRateActuatorControlTargetSvc<T>
{
type Response = super::SetRateActuatorControlTargetResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateActuatorControlTargetRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).set_rate_actuator_control_target(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateActuatorControlTargetSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateActuatorOutputStatus" => {
#[allow(non_camel_case_types)]
struct SetRateActuatorOutputStatusSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateActuatorOutputStatusRequest>
for SetRateActuatorOutputStatusSvc<T>
{
type Response = super::SetRateActuatorOutputStatusResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateActuatorOutputStatusRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).set_rate_actuator_output_status(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateActuatorOutputStatusSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateOdometry" => {
#[allow(non_camel_case_types)]
struct SetRateOdometrySvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateOdometryRequest>
for SetRateOdometrySvc<T>
{
type Response = super::SetRateOdometryResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateOdometryRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_odometry(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateOdometrySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRatePositionVelocityNed" => {
#[allow(non_camel_case_types)]
struct SetRatePositionVelocityNedSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRatePositionVelocityNedRequest>
for SetRatePositionVelocityNedSvc<T>
{
type Response = super::SetRatePositionVelocityNedResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRatePositionVelocityNedRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move {
(*inner).set_rate_position_velocity_ned(request).await
};
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRatePositionVelocityNedSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateGroundTruth" => {
#[allow(non_camel_case_types)]
struct SetRateGroundTruthSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateGroundTruthRequest>
for SetRateGroundTruthSvc<T>
{
type Response = super::SetRateGroundTruthResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateGroundTruthRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_ground_truth(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateGroundTruthSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateFixedwingMetrics" => {
#[allow(non_camel_case_types)]
struct SetRateFixedwingMetricsSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateFixedwingMetricsRequest>
for SetRateFixedwingMetricsSvc<T>
{
type Response = super::SetRateFixedwingMetricsResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateFixedwingMetricsRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_rate_fixedwing_metrics(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateFixedwingMetricsSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateImu" => {
#[allow(non_camel_case_types)]
struct SetRateImuSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService> tonic::server::UnaryService<super::SetRateImuRequest>
for SetRateImuSvc<T>
{
type Response = super::SetRateImuResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateImuRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_rate_imu(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateImuSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateUnixEpochTime" => {
#[allow(non_camel_case_types)]
struct SetRateUnixEpochTimeSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateUnixEpochTimeRequest>
for SetRateUnixEpochTimeSvc<T>
{
type Response = super::SetRateUnixEpochTimeResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateUnixEpochTimeRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_rate_unix_epoch_time(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateUnixEpochTimeSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/SetRateDistanceSensor" => {
#[allow(non_camel_case_types)]
struct SetRateDistanceSensorSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::SetRateDistanceSensorRequest>
for SetRateDistanceSensorSvc<T>
{
type Response = super::SetRateDistanceSensorResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetRateDistanceSensorRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_rate_distance_sensor(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetRateDistanceSensorSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.telemetry.TelemetryService/GetGpsGlobalOrigin" => {
#[allow(non_camel_case_types)]
struct GetGpsGlobalOriginSvc<T: TelemetryService>(pub Arc<T>);
impl<T: TelemetryService>
tonic::server::UnaryService<super::GetGpsGlobalOriginRequest>
for GetGpsGlobalOriginSvc<T>
{
type Response = super::GetGpsGlobalOriginResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::GetGpsGlobalOriginRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).get_gps_global_origin(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = GetGpsGlobalOriginSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
_ => Box::pin(async move {
Ok(http::Response::builder()
.status(200)
.header("grpc-status", "12")
.header("content-type", "application/grpc")
.body(empty_body())
.unwrap())
}),
}
}
}
impl<T: TelemetryService> Clone for TelemetryServiceServer<T> {
fn clone(&self) -> Self {
let inner = self.inner.clone();
Self {
inner,
accept_compression_encodings: self.accept_compression_encodings,
send_compression_encodings: self.send_compression_encodings,
}
}
}
impl<T: TelemetryService> Clone for _Inner<T> {
fn clone(&self) -> Self {
Self(self.0.clone())
}
}
impl<T: std::fmt::Debug> std::fmt::Debug for _Inner<T> {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
write!(f, "{:?}", self.0)
}
}
impl<T: TelemetryService> tonic::transport::NamedService for TelemetryServiceServer<T> {
const NAME: &'static str = "mavsdk.rpc.telemetry.TelemetryService";
}
}