+
+ mavsdk::Telemetry Class Reference
+#include: telemetry.h
+
+Allow users to get vehicle telemetry and state information (e.g. battery, GPS, RC connection, flight mode etc.) and set telemetry update rates.
+Data Structures
+struct AccelerationFrd
+struct ActuatorControlTarget
+struct ActuatorOutputStatus
+struct Altitude
+struct AngularVelocityBody
+struct AngularVelocityFrd
+struct Battery
+struct Covariance
+struct DistanceSensor
+struct EulerAngle
+struct FixedwingMetrics
+struct GpsGlobalOrigin
+struct GpsInfo
+struct GroundTruth
+struct Heading
+struct Health
+struct Imu
+struct MagneticFieldFrd
+struct Odometry
+struct Position
+struct PositionBody
+struct PositionNed
+struct PositionVelocityNed
+struct Quaternion
+struct RawGps
+struct RcStatus
+struct ScaledPressure
+struct StatusText
+struct VelocityBody
+struct VelocityNed
+Public Types
+
+Public Member Functions
+
+
+
+Type |
+Name |
+Description |
+
+
+
+
+ |
+Telemetry (System & system) |
+Constructor. Creates the plugin for a specific System. |
+
+
+ |
+Telemetry (std::shared_ptr< System > system) |
+Constructor. Creates the plugin for a specific System. |
+
+
+ |
+~Telemetry () override |
+Destructor (internal use only). |
+
+
+ |
+Telemetry (const Telemetry & other) |
+Copy constructor. |
+
+
+PositionHandle |
+subscribe_position (const PositionCallback & callback) |
+Subscribe to 'position' updates. |
+
+
+void |
+unsubscribe_position (PositionHandle handle) |
+Unsubscribe from subscribe_position. |
+
+
+Position |
+position () const |
+Poll for 'Position' (blocking). |
+
+
+HomeHandle |
+subscribe_home (const HomeCallback & callback) |
+Subscribe to 'home position' updates. |
+
+
+void |
+unsubscribe_home (HomeHandle handle) |
+Unsubscribe from subscribe_home. |
+
+
+Position |
+home () const |
+Poll for 'Position' (blocking). |
+
+
+InAirHandle |
+subscribe_in_air (const InAirCallback & callback) |
+Subscribe to in-air updates. |
+
+
+void |
+unsubscribe_in_air (InAirHandle handle) |
+Unsubscribe from subscribe_in_air. |
+
+
+bool |
+in_air () const |
+Poll for 'bool' (blocking). |
+
+
+LandedStateHandle |
+subscribe_landed_state (const LandedStateCallback & callback) |
+Subscribe to landed state updates. |
+
+
+void |
+unsubscribe_landed_state (LandedStateHandle handle) |
+Unsubscribe from subscribe_landed_state. |
+
+
+LandedState |
+landed_state () const |
+Poll for 'LandedState' (blocking). |
+
+
+ArmedHandle |
+subscribe_armed (const ArmedCallback & callback) |
+Subscribe to armed updates. |
+
+
+void |
+unsubscribe_armed (ArmedHandle handle) |
+Unsubscribe from subscribe_armed. |
+
+
+bool |
+armed () const |
+Poll for 'bool' (blocking). |
+
+
+VtolStateHandle |
+subscribe_vtol_state (const VtolStateCallback & callback) |
+subscribe to vtol state Updates |
+
+
+void |
+unsubscribe_vtol_state (VtolStateHandle handle) |
+Unsubscribe from subscribe_vtol_state. |
+
+
+VtolState |
+vtol_state () const |
+Poll for 'VtolState' (blocking). |
+
+
+AttitudeQuaternionHandle |
+subscribe_attitude_quaternion (const AttitudeQuaternionCallback & callback) |
+Subscribe to 'attitude' updates (quaternion). |
+
+
+void |
+unsubscribe_attitude_quaternion (AttitudeQuaternionHandle handle) |
+Unsubscribe from subscribe_attitude_quaternion. |
+
+
+Quaternion |
+attitude_quaternion () const |
+Poll for 'Quaternion' (blocking). |
+
+
+AttitudeEulerHandle |
+subscribe_attitude_euler (const AttitudeEulerCallback & callback) |
+Subscribe to 'attitude' updates (Euler). |
+
+
+void |
+unsubscribe_attitude_euler (AttitudeEulerHandle handle) |
+Unsubscribe from subscribe_attitude_euler. |
+
+
+EulerAngle |
+attitude_euler () const |
+Poll for 'EulerAngle' (blocking). |
+
+
+AttitudeAngularVelocityBodyHandle |
+subscribe_attitude_angular_velocity_body (const AttitudeAngularVelocityBodyCallback & callback) |
+Subscribe to 'attitude' updates (angular velocity) |
+
+
+void |
+unsubscribe_attitude_angular_velocity_body (AttitudeAngularVelocityBodyHandle handle) |
+Unsubscribe from subscribe_attitude_angular_velocity_body. |
+
+
+AngularVelocityBody |
+attitude_angular_velocity_body () const |
+Poll for 'AngularVelocityBody' (blocking). |
+
+
+CameraAttitudeQuaternionHandle |
+subscribe_camera_attitude_quaternion (const CameraAttitudeQuaternionCallback & callback) |
+Subscribe to 'camera attitude' updates (quaternion). |
+
+
+void |
+unsubscribe_camera_attitude_quaternion (CameraAttitudeQuaternionHandle handle) |
+Unsubscribe from subscribe_camera_attitude_quaternion. |
+
+
+Quaternion |
+camera_attitude_quaternion () const |
+Poll for 'Quaternion' (blocking). |
+
+
+CameraAttitudeEulerHandle |
+subscribe_camera_attitude_euler (const CameraAttitudeEulerCallback & callback) |
+Subscribe to 'camera attitude' updates (Euler). |
+
+
+void |
+unsubscribe_camera_attitude_euler (CameraAttitudeEulerHandle handle) |
+Unsubscribe from subscribe_camera_attitude_euler. |
+
+
+EulerAngle |
+camera_attitude_euler () const |
+Poll for 'EulerAngle' (blocking). |
+
+
+VelocityNedHandle |
+subscribe_velocity_ned (const VelocityNedCallback & callback) |
+Subscribe to 'ground speed' updates (NED). |
+
+
+void |
+unsubscribe_velocity_ned (VelocityNedHandle handle) |
+Unsubscribe from subscribe_velocity_ned. |
+
+
+VelocityNed |
+velocity_ned () const |
+Poll for 'VelocityNed' (blocking). |
+
+
+GpsInfoHandle |
+subscribe_gps_info (const GpsInfoCallback & callback) |
+Subscribe to 'GPS info' updates. |
+
+
+void |
+unsubscribe_gps_info (GpsInfoHandle handle) |
+Unsubscribe from subscribe_gps_info. |
+
+
+GpsInfo |
+gps_info () const |
+Poll for 'GpsInfo' (blocking). |
+
+
+RawGpsHandle |
+subscribe_raw_gps (const RawGpsCallback & callback) |
+Subscribe to 'Raw GPS' updates. |
+
+
+void |
+unsubscribe_raw_gps (RawGpsHandle handle) |
+Unsubscribe from subscribe_raw_gps. |
+
+
+RawGps |
+raw_gps () const |
+Poll for 'RawGps' (blocking). |
+
+
+BatteryHandle |
+subscribe_battery (const BatteryCallback & callback) |
+Subscribe to 'battery' updates. |
+
+
+void |
+unsubscribe_battery (BatteryHandle handle) |
+Unsubscribe from subscribe_battery. |
+
+
+Battery |
+battery () const |
+Poll for 'Battery' (blocking). |
+
+
+FlightModeHandle |
+subscribe_flight_mode (const FlightModeCallback & callback) |
+Subscribe to 'flight mode' updates. |
+
+
+void |
+unsubscribe_flight_mode (FlightModeHandle handle) |
+Unsubscribe from subscribe_flight_mode. |
+
+
+FlightMode |
+flight_mode () const |
+Poll for 'FlightMode' (blocking). |
+
+
+HealthHandle |
+subscribe_health (const HealthCallback & callback) |
+Subscribe to 'health' updates. |
+
+
+void |
+unsubscribe_health (HealthHandle handle) |
+Unsubscribe from subscribe_health. |
+
+
+Health |
+health () const |
+Poll for 'Health' (blocking). |
+
+
+RcStatusHandle |
+subscribe_rc_status (const RcStatusCallback & callback) |
+Subscribe to 'RC status' updates. |
+
+
+void |
+unsubscribe_rc_status (RcStatusHandle handle) |
+Unsubscribe from subscribe_rc_status. |
+
+
+RcStatus |
+rc_status () const |
+Poll for 'RcStatus' (blocking). |
+
+
+StatusTextHandle |
+subscribe_status_text (const StatusTextCallback & callback) |
+Subscribe to 'status text' updates. |
+
+
+void |
+unsubscribe_status_text (StatusTextHandle handle) |
+Unsubscribe from subscribe_status_text. |
+
+
+StatusText |
+status_text () const |
+Poll for 'StatusText' (blocking). |
+
+
+ActuatorControlTargetHandle |
+subscribe_actuator_control_target (const ActuatorControlTargetCallback & callback) |
+Subscribe to 'actuator control target' updates. |
+
+
+void |
+unsubscribe_actuator_control_target (ActuatorControlTargetHandle handle) |
+Unsubscribe from subscribe_actuator_control_target. |
+
+
+ActuatorControlTarget |
+actuator_control_target () const |
+Poll for 'ActuatorControlTarget' (blocking). |
+
+
+ActuatorOutputStatusHandle |
+subscribe_actuator_output_status (const ActuatorOutputStatusCallback & callback) |
+Subscribe to 'actuator output status' updates. |
+
+
+void |
+unsubscribe_actuator_output_status (ActuatorOutputStatusHandle handle) |
+Unsubscribe from subscribe_actuator_output_status. |
+
+
+ActuatorOutputStatus |
+actuator_output_status () const |
+Poll for 'ActuatorOutputStatus' (blocking). |
+
+
+OdometryHandle |
+subscribe_odometry (const OdometryCallback & callback) |
+Subscribe to 'odometry' updates. |
+
+
+void |
+unsubscribe_odometry (OdometryHandle handle) |
+Unsubscribe from subscribe_odometry. |
+
+
+Odometry |
+odometry () const |
+Poll for 'Odometry' (blocking). |
+
+
+PositionVelocityNedHandle |
+subscribe_position_velocity_ned (const PositionVelocityNedCallback & callback) |
+Subscribe to 'position velocity' updates. |
+
+
+void |
+unsubscribe_position_velocity_ned (PositionVelocityNedHandle handle) |
+Unsubscribe from subscribe_position_velocity_ned. |
+
+
+PositionVelocityNed |
+position_velocity_ned () const |
+Poll for 'PositionVelocityNed' (blocking). |
+
+
+GroundTruthHandle |
+subscribe_ground_truth (const GroundTruthCallback & callback) |
+Subscribe to 'ground truth' updates. |
+
+
+void |
+unsubscribe_ground_truth (GroundTruthHandle handle) |
+Unsubscribe from subscribe_ground_truth. |
+
+
+GroundTruth |
+ground_truth () const |
+Poll for 'GroundTruth' (blocking). |
+
+
+FixedwingMetricsHandle |
+subscribe_fixedwing_metrics (const FixedwingMetricsCallback & callback) |
+Subscribe to 'fixedwing metrics' updates. |
+
+
+void |
+unsubscribe_fixedwing_metrics (FixedwingMetricsHandle handle) |
+Unsubscribe from subscribe_fixedwing_metrics. |
+
+
+FixedwingMetrics |
+fixedwing_metrics () const |
+Poll for 'FixedwingMetrics' (blocking). |
+
+
+ImuHandle |
+subscribe_imu (const ImuCallback & callback) |
+Subscribe to 'IMU' updates (in SI units in NED body frame). |
+
+
+void |
+unsubscribe_imu (ImuHandle handle) |
+Unsubscribe from subscribe_imu. |
+
+
+Imu |
+imu () const |
+Poll for 'Imu' (blocking). |
+
+
+ScaledImuHandle |
+subscribe_scaled_imu (const ScaledImuCallback & callback) |
+Subscribe to 'Scaled IMU' updates. |
+
+
+void |
+unsubscribe_scaled_imu (ScaledImuHandle handle) |
+Unsubscribe from subscribe_scaled_imu. |
+
+
+Imu |
+scaled_imu () const |
+Poll for 'Imu' (blocking). |
+
+
+RawImuHandle |
+subscribe_raw_imu (const RawImuCallback & callback) |
+Subscribe to 'Raw IMU' updates. |
+
+
+void |
+unsubscribe_raw_imu (RawImuHandle handle) |
+Unsubscribe from subscribe_raw_imu. |
+
+
+Imu |
+raw_imu () const |
+Poll for 'Imu' (blocking). |
+
+
+HealthAllOkHandle |
+subscribe_health_all_ok (const HealthAllOkCallback & callback) |
+Subscribe to 'HealthAllOk' updates. |
+
+
+void |
+unsubscribe_health_all_ok (HealthAllOkHandle handle) |
+Unsubscribe from subscribe_health_all_ok. |
+
+
+bool |
+health_all_ok () const |
+Poll for 'bool' (blocking). |
+
+
+UnixEpochTimeHandle |
+subscribe_unix_epoch_time (const UnixEpochTimeCallback & callback) |
+Subscribe to 'unix epoch time' updates. |
+
+
+void |
+unsubscribe_unix_epoch_time (UnixEpochTimeHandle handle) |
+Unsubscribe from subscribe_unix_epoch_time. |
+
+
+uint64_t |
+unix_epoch_time () const |
+Poll for 'uint64_t' (blocking). |
+
+
+DistanceSensorHandle |
+subscribe_distance_sensor (const DistanceSensorCallback & callback) |
+Subscribe to 'Distance Sensor' updates. |
+
+
+void |
+unsubscribe_distance_sensor (DistanceSensorHandle handle) |
+Unsubscribe from subscribe_distance_sensor. |
+
+
+DistanceSensor |
+distance_sensor () const |
+Poll for 'DistanceSensor' (blocking). |
+
+
+ScaledPressureHandle |
+subscribe_scaled_pressure (const ScaledPressureCallback & callback) |
+Subscribe to 'Scaled Pressure' updates. |
+
+
+void |
+unsubscribe_scaled_pressure (ScaledPressureHandle handle) |
+Unsubscribe from subscribe_scaled_pressure. |
+
+
+ScaledPressure |
+scaled_pressure () const |
+Poll for 'ScaledPressure' (blocking). |
+
+
+HeadingHandle |
+subscribe_heading (const HeadingCallback & callback) |
+Subscribe to 'Heading' updates. |
+
+
+void |
+unsubscribe_heading (HeadingHandle handle) |
+Unsubscribe from subscribe_heading. |
+
+
+Heading |
+heading () const |
+Poll for 'Heading' (blocking). |
+
+
+AltitudeHandle |
+subscribe_altitude (const AltitudeCallback & callback) |
+Subscribe to 'Altitude' updates. |
+
+
+void |
+unsubscribe_altitude (AltitudeHandle handle) |
+Unsubscribe from subscribe_altitude. |
+
+
+Altitude |
+altitude () const |
+Poll for 'Altitude' (blocking). |
+
+
+void |
+set_rate_position_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'position' updates. |
+
+
+Result |
+set_rate_position (double rate_hz)const |
+Set rate to 'position' updates. |
+
+
+void |
+set_rate_home_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'home position' updates. |
+
+
+Result |
+set_rate_home (double rate_hz)const |
+Set rate to 'home position' updates. |
+
+
+void |
+set_rate_in_air_async (double rate_hz, const ResultCallback callback) |
+Set rate to in-air updates. |
+
+
+Result |
+set_rate_in_air (double rate_hz)const |
+Set rate to in-air updates. |
+
+
+void |
+set_rate_landed_state_async (double rate_hz, const ResultCallback callback) |
+Set rate to landed state updates. |
+
+
+Result |
+set_rate_landed_state (double rate_hz)const |
+Set rate to landed state updates. |
+
+
+void |
+set_rate_vtol_state_async (double rate_hz, const ResultCallback callback) |
+Set rate to VTOL state updates. |
+
+
+Result |
+set_rate_vtol_state (double rate_hz)const |
+Set rate to VTOL state updates. |
+
+
+void |
+set_rate_attitude_quaternion_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'attitude euler angle' updates. |
+
+
+Result |
+set_rate_attitude_quaternion (double rate_hz)const |
+Set rate to 'attitude euler angle' updates. |
+
+
+void |
+set_rate_attitude_euler_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'attitude quaternion' updates. |
+
+
+Result |
+set_rate_attitude_euler (double rate_hz)const |
+Set rate to 'attitude quaternion' updates. |
+
+
+void |
+set_rate_camera_attitude_async (double rate_hz, const ResultCallback callback) |
+Set rate of camera attitude updates. |
+
+
+Result |
+set_rate_camera_attitude (double rate_hz)const |
+Set rate of camera attitude updates. |
+
+
+void |
+set_rate_velocity_ned_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'ground speed' updates (NED). |
+
+
+Result |
+set_rate_velocity_ned (double rate_hz)const |
+Set rate to 'ground speed' updates (NED). |
+
+
+void |
+set_rate_gps_info_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'GPS info' updates. |
+
+
+Result |
+set_rate_gps_info (double rate_hz)const |
+Set rate to 'GPS info' updates. |
+
+
+void |
+set_rate_battery_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'battery' updates. |
+
+
+Result |
+set_rate_battery (double rate_hz)const |
+Set rate to 'battery' updates. |
+
+
+void |
+set_rate_rc_status_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'RC status' updates. |
+
+
+Result |
+set_rate_rc_status (double rate_hz)const |
+Set rate to 'RC status' updates. |
+
+
+void |
+set_rate_actuator_control_target_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'actuator control target' updates. |
+
+
+Result |
+set_rate_actuator_control_target (double rate_hz)const |
+Set rate to 'actuator control target' updates. |
+
+
+void |
+set_rate_actuator_output_status_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'actuator output status' updates. |
+
+
+Result |
+set_rate_actuator_output_status (double rate_hz)const |
+Set rate to 'actuator output status' updates. |
+
+
+void |
+set_rate_odometry_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'odometry' updates. |
+
+
+Result |
+set_rate_odometry (double rate_hz)const |
+Set rate to 'odometry' updates. |
+
+
+void |
+set_rate_position_velocity_ned_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'position velocity' updates. |
+
+
+Result |
+set_rate_position_velocity_ned (double rate_hz)const |
+Set rate to 'position velocity' updates. |
+
+
+void |
+set_rate_ground_truth_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'ground truth' updates. |
+
+
+Result |
+set_rate_ground_truth (double rate_hz)const |
+Set rate to 'ground truth' updates. |
+
+
+void |
+set_rate_fixedwing_metrics_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'fixedwing metrics' updates. |
+
+
+Result |
+set_rate_fixedwing_metrics (double rate_hz)const |
+Set rate to 'fixedwing metrics' updates. |
+
+
+void |
+set_rate_imu_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'IMU' updates. |
+
+
+Result |
+set_rate_imu (double rate_hz)const |
+Set rate to 'IMU' updates. |
+
+
+void |
+set_rate_scaled_imu_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'Scaled IMU' updates. |
+
+
+Result |
+set_rate_scaled_imu (double rate_hz)const |
+Set rate to 'Scaled IMU' updates. |
+
+
+void |
+set_rate_raw_imu_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'Raw IMU' updates. |
+
+
+Result |
+set_rate_raw_imu (double rate_hz)const |
+Set rate to 'Raw IMU' updates. |
+
+
+void |
+set_rate_unix_epoch_time_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'unix epoch time' updates. |
+
+
+Result |
+set_rate_unix_epoch_time (double rate_hz)const |
+Set rate to 'unix epoch time' updates. |
+
+
+void |
+set_rate_distance_sensor_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'Distance Sensor' updates. |
+
+
+Result |
+set_rate_distance_sensor (double rate_hz)const |
+Set rate to 'Distance Sensor' updates. |
+
+
+void |
+set_rate_altitude_async (double rate_hz, const ResultCallback callback) |
+Set rate to 'Altitude' updates. |
+
+
+Result |
+set_rate_altitude (double rate_hz)const |
+Set rate to 'Altitude' updates. |
+
+
+void |
+get_gps_global_origin_async (const GetGpsGlobalOriginCallback callback) |
+Get the GPS location of where the estimator has been initialized. |
+
+
+std::pair< Result, Telemetry::GpsGlobalOrigin > |
+get_gps_global_origin () const |
+Get the GPS location of where the estimator has been initialized. |
+
+
+const Telemetry & |
+operator= (const Telemetry &)=delete |
+Equality operator (object is not copyable). |
+
+
+
+Constructor & Destructor Documentation
+Telemetry()
+mavsdk::Telemetry::Telemetry(System &system)
+
+Constructor. Creates the plugin for a specific System.
+The plugin is typically created as shown below:
+auto telemetry = Telemetry(system);
+
+Parameters
+
+- System& system - The specific system associated with this plugin.
+
+Telemetry()
+mavsdk::Telemetry::Telemetry(std::shared_ptr< System > system)
+
+Constructor. Creates the plugin for a specific System.
+The plugin is typically created as shown below:
+auto telemetry = Telemetry(system);
+
+Parameters
+
+- std::shared_ptr< System > system - The specific system associated with this plugin.
+
+~Telemetry()
+mavsdk::Telemetry::~Telemetry() override
+
+Destructor (internal use only).
+Telemetry()
+mavsdk::Telemetry::Telemetry(const Telemetry &other)
+
+Copy constructor.
+Parameters
+
+Member Typdef Documentation
+typedef ResultCallback
+using mavsdk::Telemetry::ResultCallback = std::function<void(Result)>
+
+Callback type for asynchronous Telemetry calls.
+typedef PositionCallback
+using mavsdk::Telemetry::PositionCallback = std::function<void(Position)>
+
+Callback type for subscribe_position.
+typedef PositionHandle
+using mavsdk::Telemetry::PositionHandle = Handle<Position>
+
+Handle type for subscribe_position.
+typedef HomeCallback
+using mavsdk::Telemetry::HomeCallback = std::function<void(Position)>
+
+Callback type for subscribe_home.
+typedef HomeHandle
+using mavsdk::Telemetry::HomeHandle = Handle<Position>
+
+Handle type for subscribe_home.
+typedef InAirCallback
+using mavsdk::Telemetry::InAirCallback = std::function<void(bool)>
+
+Callback type for subscribe_in_air.
+typedef InAirHandle
+using mavsdk::Telemetry::InAirHandle = Handle<bool>
+
+Handle type for subscribe_in_air.
+typedef LandedStateCallback
+using mavsdk::Telemetry::LandedStateCallback = std::function<void(LandedState)>
+
+Callback type for subscribe_landed_state.
+typedef LandedStateHandle
+using mavsdk::Telemetry::LandedStateHandle = Handle<LandedState>
+
+Handle type for subscribe_landed_state.
+typedef ArmedCallback
+using mavsdk::Telemetry::ArmedCallback = std::function<void(bool)>
+
+Callback type for subscribe_armed.
+typedef ArmedHandle
+using mavsdk::Telemetry::ArmedHandle = Handle<bool>
+
+Handle type for subscribe_armed.
+typedef VtolStateCallback
+using mavsdk::Telemetry::VtolStateCallback = std::function<void(VtolState)>
+
+Callback type for subscribe_vtol_state.
+typedef VtolStateHandle
+using mavsdk::Telemetry::VtolStateHandle = Handle<VtolState>
+
+Handle type for subscribe_vtol_state.
+typedef AttitudeQuaternionCallback
+using mavsdk::Telemetry::AttitudeQuaternionCallback = std::function<void(Quaternion)>
+
+Callback type for subscribe_attitude_quaternion.
+typedef AttitudeQuaternionHandle
+using mavsdk::Telemetry::AttitudeQuaternionHandle = Handle<Quaternion>
+
+Handle type for subscribe_attitude_quaternion.
+typedef AttitudeEulerCallback
+using mavsdk::Telemetry::AttitudeEulerCallback = std::function<void(EulerAngle)>
+
+Callback type for subscribe_attitude_euler.
+typedef AttitudeEulerHandle
+using mavsdk::Telemetry::AttitudeEulerHandle = Handle<EulerAngle>
+
+Handle type for subscribe_attitude_euler.
+typedef AttitudeAngularVelocityBodyCallback
+using mavsdk::Telemetry::AttitudeAngularVelocityBodyCallback = std::function<void(AngularVelocityBody)>
+
+Callback type for subscribe_attitude_angular_velocity_body.
+typedef AttitudeAngularVelocityBodyHandle
+using mavsdk::Telemetry::AttitudeAngularVelocityBodyHandle = Handle<AngularVelocityBody>
+
+Handle type for subscribe_attitude_angular_velocity_body.
+typedef CameraAttitudeQuaternionCallback
+using mavsdk::Telemetry::CameraAttitudeQuaternionCallback = std::function<void(Quaternion)>
+
+Callback type for subscribe_camera_attitude_quaternion.
+typedef CameraAttitudeQuaternionHandle
+using mavsdk::Telemetry::CameraAttitudeQuaternionHandle = Handle<Quaternion>
+
+Handle type for subscribe_camera_attitude_quaternion.
+typedef CameraAttitudeEulerCallback
+using mavsdk::Telemetry::CameraAttitudeEulerCallback = std::function<void(EulerAngle)>
+
+Callback type for subscribe_camera_attitude_euler.
+typedef CameraAttitudeEulerHandle
+using mavsdk::Telemetry::CameraAttitudeEulerHandle = Handle<EulerAngle>
+
+Handle type for subscribe_camera_attitude_euler.
+typedef VelocityNedCallback
+using mavsdk::Telemetry::VelocityNedCallback = std::function<void(VelocityNed)>
+
+Callback type for subscribe_velocity_ned.
+typedef VelocityNedHandle
+using mavsdk::Telemetry::VelocityNedHandle = Handle<VelocityNed>
+
+Handle type for subscribe_velocity_ned.
+typedef GpsInfoCallback
+using mavsdk::Telemetry::GpsInfoCallback = std::function<void(GpsInfo)>
+
+Callback type for subscribe_gps_info.
+typedef GpsInfoHandle
+using mavsdk::Telemetry::GpsInfoHandle = Handle<GpsInfo>
+
+Handle type for subscribe_gps_info.
+typedef RawGpsCallback
+using mavsdk::Telemetry::RawGpsCallback = std::function<void(RawGps)>
+
+Callback type for subscribe_raw_gps.
+typedef RawGpsHandle
+using mavsdk::Telemetry::RawGpsHandle = Handle<RawGps>
+
+Handle type for subscribe_raw_gps.
+typedef BatteryCallback
+using mavsdk::Telemetry::BatteryCallback = std::function<void(Battery)>
+
+Callback type for subscribe_battery.
+typedef BatteryHandle
+using mavsdk::Telemetry::BatteryHandle = Handle<Battery>
+
+Handle type for subscribe_battery.
+typedef FlightModeCallback
+using mavsdk::Telemetry::FlightModeCallback = std::function<void(FlightMode)>
+
+Callback type for subscribe_flight_mode.
+typedef FlightModeHandle
+using mavsdk::Telemetry::FlightModeHandle = Handle<FlightMode>
+
+Handle type for subscribe_flight_mode.
+typedef HealthCallback
+using mavsdk::Telemetry::HealthCallback = std::function<void(Health)>
+
+Callback type for subscribe_health.
+typedef HealthHandle
+using mavsdk::Telemetry::HealthHandle = Handle<Health>
+
+Handle type for subscribe_health.
+typedef RcStatusCallback
+using mavsdk::Telemetry::RcStatusCallback = std::function<void(RcStatus)>
+
+Callback type for subscribe_rc_status.
+typedef RcStatusHandle
+using mavsdk::Telemetry::RcStatusHandle = Handle<RcStatus>
+
+Handle type for subscribe_rc_status.
+typedef StatusTextCallback
+using mavsdk::Telemetry::StatusTextCallback = std::function<void(StatusText)>
+
+Callback type for subscribe_status_text.
+typedef StatusTextHandle
+using mavsdk::Telemetry::StatusTextHandle = Handle<StatusText>
+
+Handle type for subscribe_status_text.
+typedef ActuatorControlTargetCallback
+using mavsdk::Telemetry::ActuatorControlTargetCallback = std::function<void(ActuatorControlTarget)>
+
+Callback type for subscribe_actuator_control_target.
+typedef ActuatorControlTargetHandle
+using mavsdk::Telemetry::ActuatorControlTargetHandle = Handle<ActuatorControlTarget>
+
+Handle type for subscribe_actuator_control_target.
+typedef ActuatorOutputStatusCallback
+using mavsdk::Telemetry::ActuatorOutputStatusCallback = std::function<void(ActuatorOutputStatus)>
+
+Callback type for subscribe_actuator_output_status.
+typedef ActuatorOutputStatusHandle
+using mavsdk::Telemetry::ActuatorOutputStatusHandle = Handle<ActuatorOutputStatus>
+
+Handle type for subscribe_actuator_output_status.
+typedef OdometryCallback
+using mavsdk::Telemetry::OdometryCallback = std::function<void(Odometry)>
+
+Callback type for subscribe_odometry.
+typedef OdometryHandle
+using mavsdk::Telemetry::OdometryHandle = Handle<Odometry>
+
+Handle type for subscribe_odometry.
+typedef PositionVelocityNedCallback
+using mavsdk::Telemetry::PositionVelocityNedCallback = std::function<void(PositionVelocityNed)>
+
+Callback type for subscribe_position_velocity_ned.
+typedef PositionVelocityNedHandle
+using mavsdk::Telemetry::PositionVelocityNedHandle = Handle<PositionVelocityNed>
+
+Handle type for subscribe_position_velocity_ned.
+typedef GroundTruthCallback
+using mavsdk::Telemetry::GroundTruthCallback = std::function<void(GroundTruth)>
+
+Callback type for subscribe_ground_truth.
+typedef GroundTruthHandle
+using mavsdk::Telemetry::GroundTruthHandle = Handle<GroundTruth>
+
+Handle type for subscribe_ground_truth.
+typedef FixedwingMetricsCallback
+using mavsdk::Telemetry::FixedwingMetricsCallback = std::function<void(FixedwingMetrics)>
+
+Callback type for subscribe_fixedwing_metrics.
+typedef FixedwingMetricsHandle
+using mavsdk::Telemetry::FixedwingMetricsHandle = Handle<FixedwingMetrics>
+
+Handle type for subscribe_fixedwing_metrics.
+typedef ImuCallback
+using mavsdk::Telemetry::ImuCallback = std::function<void(Imu)>
+
+Callback type for subscribe_imu.
+typedef ImuHandle
+using mavsdk::Telemetry::ImuHandle = Handle<Imu>
+
+Handle type for subscribe_imu.
+typedef ScaledImuCallback
+using mavsdk::Telemetry::ScaledImuCallback = std::function<void(Imu)>
+
+Callback type for subscribe_scaled_imu.
+typedef ScaledImuHandle
+using mavsdk::Telemetry::ScaledImuHandle = Handle<Imu>
+
+Handle type for subscribe_scaled_imu.
+typedef RawImuCallback
+using mavsdk::Telemetry::RawImuCallback = std::function<void(Imu)>
+
+Callback type for subscribe_raw_imu.
+typedef RawImuHandle
+using mavsdk::Telemetry::RawImuHandle = Handle<Imu>
+
+Handle type for subscribe_raw_imu.
+typedef HealthAllOkCallback
+using mavsdk::Telemetry::HealthAllOkCallback = std::function<void(bool)>
+
+Callback type for subscribe_health_all_ok.
+typedef HealthAllOkHandle
+using mavsdk::Telemetry::HealthAllOkHandle = Handle<bool>
+
+Handle type for subscribe_health_all_ok.
+typedef UnixEpochTimeCallback
+using mavsdk::Telemetry::UnixEpochTimeCallback = std::function<void(uint64_t)>
+
+Callback type for subscribe_unix_epoch_time.
+typedef UnixEpochTimeHandle
+using mavsdk::Telemetry::UnixEpochTimeHandle = Handle<uint64_t>
+
+Handle type for subscribe_unix_epoch_time.
+typedef DistanceSensorCallback
+using mavsdk::Telemetry::DistanceSensorCallback = std::function<void(DistanceSensor)>
+
+Callback type for subscribe_distance_sensor.
+typedef DistanceSensorHandle
+using mavsdk::Telemetry::DistanceSensorHandle = Handle<DistanceSensor>
+
+Handle type for subscribe_distance_sensor.
+typedef ScaledPressureCallback
+using mavsdk::Telemetry::ScaledPressureCallback = std::function<void(ScaledPressure)>
+
+Callback type for subscribe_scaled_pressure.
+typedef ScaledPressureHandle
+using mavsdk::Telemetry::ScaledPressureHandle = Handle<ScaledPressure>
+
+Handle type for subscribe_scaled_pressure.
+typedef HeadingCallback
+using mavsdk::Telemetry::HeadingCallback = std::function<void(Heading)>
+
+Callback type for subscribe_heading.
+typedef HeadingHandle
+using mavsdk::Telemetry::HeadingHandle = Handle<Heading>
+
+Handle type for subscribe_heading.
+typedef AltitudeCallback
+using mavsdk::Telemetry::AltitudeCallback = std::function<void(Altitude)>
+
+Callback type for subscribe_altitude.
+typedef AltitudeHandle
+using mavsdk::Telemetry::AltitudeHandle = Handle<Altitude>
+
+Handle type for subscribe_altitude.
+typedef GetGpsGlobalOriginCallback
+using mavsdk::Telemetry::GetGpsGlobalOriginCallback = std::function<void(Result, GpsGlobalOrigin)>
+
+Callback type for get_gps_global_origin_async.
+Member Enumeration Documentation
+enum FixType
+GPS fix type.
+
+
+
+Value |
+Description |
+
+
+
+
+ NoGps |
+No GPS connected. |
+
+
+ NoFix |
+No position information, GPS is connected. |
+
+
+ Fix2D |
+2D position. |
+
+
+ Fix3D |
+3D position. |
+
+
+ FixDgps |
+DGPS/SBAS aided 3D position. |
+
+
+ RtkFloat |
+RTK float, 3D position. |
+
+
+ RtkFixed |
+RTK Fixed, 3D position. |
+
+
+
+enum FlightMode
+Flight modes.
+For more information about flight modes, check out https://docs.px4.io/master/en/config/flight_mode.html.
+
+
+
+Value |
+Description |
+
+
+
+
+ Unknown |
+Mode not known. |
+
+
+ Ready |
+Armed and ready to take off. |
+
+
+ Takeoff |
+Taking off. |
+
+
+ Hold |
+Holding (hovering in place (or circling for fixed-wing vehicles). |
+
+
+ Mission |
+In mission. |
+
+
+ ReturnToLaunch |
+Returning to launch position (then landing). |
+
+
+ Land |
+Landing. |
+
+
+ Offboard |
+In 'offboard' mode. |
+
+
+ FollowMe |
+In 'follow-me' mode. |
+
+
+ Manual |
+In 'Manual' mode. |
+
+
+ Altctl |
+In 'Altitude Control' mode. |
+
+
+ Posctl |
+In 'Position Control' mode. |
+
+
+ Acro |
+In 'Acro' mode. |
+
+
+ Stabilized |
+In 'Stabilize' mode. |
+
+
+ Rattitude |
+In 'Rattitude' mode. |
+
+
+
+enum StatusTextType
+Status types.
+
+
+
+Value |
+Description |
+
+
+
+
+ Debug |
+Debug. |
+
+
+ Info |
+Information. |
+
+
+ Notice |
+Notice. |
+
+
+ Warning |
+Warning. |
+
+
+ Error |
+Error. |
+
+
+ Critical |
+Critical. |
+
+
+ Alert |
+Alert. |
+
+
+ Emergency |
+Emergency. |
+
+
+
+enum LandedState
+Landed State enumeration.
+
+
+
+Value |
+Description |
+
+
+
+
+ Unknown |
+Landed state is unknown. |
+
+
+ OnGround |
+The vehicle is on the ground. |
+
+
+ InAir |
+The vehicle is in the air. |
+
+
+ TakingOff |
+The vehicle is taking off. |
+
+
+ Landing |
+The vehicle is landing. |
+
+
+
+enum VtolState
+VTOL State enumeration.
+
+
+
+Value |
+Description |
+
+
+
+
+ Undefined |
+MAV is not configured as VTOL. |
+
+
+ TransitionToFw |
+VTOL is in transition from multicopter to fixed-wing. |
+
+
+ TransitionToMc |
+VTOL is in transition from fixed-wing to multicopter. |
+
+
+ Mc |
+VTOL is in multicopter state. |
+
+
+ Fw |
+VTOL is in fixed-wing state. |
+
+
+
+enum Result
+Possible results returned for telemetry requests.
+
+
+
+Value |
+Description |
+
+
+
+
+ Unknown |
+Unknown result. |
+
+
+ Success |
+Success: the telemetry command was accepted by the vehicle. |
+
+
+ NoSystem |
+No system connected. |
+
+
+ ConnectionError |
+Connection error. |
+
+
+ Busy |
+Vehicle is busy. |
+
+
+ CommandDenied |
+Command refused by vehicle. |
+
+
+ Timeout |
+Request timed out. |
+
+
+ Unsupported |
+Request not supported. |
+
+
+
+Member Function Documentation
+subscribe_position()
+PositionHandle mavsdk::Telemetry::subscribe_position(const PositionCallback &callback)
+
+Subscribe to 'position' updates.
+Parameters
+
+Returns
+ PositionHandle -
+unsubscribe_position()
+void mavsdk::Telemetry::unsubscribe_position(PositionHandle handle)
+
+Unsubscribe from subscribe_position.
+Parameters
+
+position()
+Position mavsdk::Telemetry::position() const
+
+Poll for 'Position' (blocking).
+Returns
+ Position - One Position update.
+subscribe_home()
+HomeHandle mavsdk::Telemetry::subscribe_home(const HomeCallback &callback)
+
+Subscribe to 'home position' updates.
+Parameters
+
+Returns
+ HomeHandle -
+unsubscribe_home()
+void mavsdk::Telemetry::unsubscribe_home(HomeHandle handle)
+
+Unsubscribe from subscribe_home.
+Parameters
+
+home()
+Position mavsdk::Telemetry::home() const
+
+Poll for 'Position' (blocking).
+Returns
+ Position - One Position update.
+subscribe_in_air()
+InAirHandle mavsdk::Telemetry::subscribe_in_air(const InAirCallback &callback)
+
+Subscribe to in-air updates.
+Parameters
+
+Returns
+ InAirHandle -
+unsubscribe_in_air()
+void mavsdk::Telemetry::unsubscribe_in_air(InAirHandle handle)
+
+Unsubscribe from subscribe_in_air.
+Parameters
+
+in_air()
+bool mavsdk::Telemetry::in_air() const
+
+Poll for 'bool' (blocking).
+Returns
+ bool - One bool update.
+subscribe_landed_state()
+LandedStateHandle mavsdk::Telemetry::subscribe_landed_state(const LandedStateCallback &callback)
+
+Subscribe to landed state updates.
+Parameters
+
+Returns
+ LandedStateHandle -
+unsubscribe_landed_state()
+void mavsdk::Telemetry::unsubscribe_landed_state(LandedStateHandle handle)
+
+Unsubscribe from subscribe_landed_state.
+Parameters
+
+landed_state()
+LandedState mavsdk::Telemetry::landed_state() const
+
+Poll for 'LandedState' (blocking).
+Returns
+ LandedState - One LandedState update.
+subscribe_armed()
+ArmedHandle mavsdk::Telemetry::subscribe_armed(const ArmedCallback &callback)
+
+Subscribe to armed updates.
+Parameters
+
+Returns
+ ArmedHandle -
+unsubscribe_armed()
+void mavsdk::Telemetry::unsubscribe_armed(ArmedHandle handle)
+
+Unsubscribe from subscribe_armed.
+Parameters
+
+armed()
+bool mavsdk::Telemetry::armed() const
+
+Poll for 'bool' (blocking).
+Returns
+ bool - One bool update.
+subscribe_vtol_state()
+VtolStateHandle mavsdk::Telemetry::subscribe_vtol_state(const VtolStateCallback &callback)
+
+subscribe to vtol state Updates
+Parameters
+
+Returns
+ VtolStateHandle -
+unsubscribe_vtol_state()
+void mavsdk::Telemetry::unsubscribe_vtol_state(VtolStateHandle handle)
+
+Unsubscribe from subscribe_vtol_state.
+Parameters
+
+vtol_state()
+VtolState mavsdk::Telemetry::vtol_state() const
+
+Poll for 'VtolState' (blocking).
+Returns
+ VtolState - One VtolState update.
+subscribe_attitude_quaternion()
+AttitudeQuaternionHandle mavsdk::Telemetry::subscribe_attitude_quaternion(const AttitudeQuaternionCallback &callback)
+
+Subscribe to 'attitude' updates (quaternion).
+Parameters
+
+Returns
+ AttitudeQuaternionHandle -
+unsubscribe_attitude_quaternion()
+void mavsdk::Telemetry::unsubscribe_attitude_quaternion(AttitudeQuaternionHandle handle)
+
+Unsubscribe from subscribe_attitude_quaternion.
+Parameters
+
+attitude_quaternion()
+Quaternion mavsdk::Telemetry::attitude_quaternion() const
+
+Poll for 'Quaternion' (blocking).
+Returns
+ Quaternion - One Quaternion update.
+subscribe_attitude_euler()
+AttitudeEulerHandle mavsdk::Telemetry::subscribe_attitude_euler(const AttitudeEulerCallback &callback)
+
+Subscribe to 'attitude' updates (Euler).
+Parameters
+
+Returns
+ AttitudeEulerHandle -
+unsubscribe_attitude_euler()
+void mavsdk::Telemetry::unsubscribe_attitude_euler(AttitudeEulerHandle handle)
+
+Unsubscribe from subscribe_attitude_euler.
+Parameters
+
+attitude_euler()
+EulerAngle mavsdk::Telemetry::attitude_euler() const
+
+Poll for 'EulerAngle' (blocking).
+Returns
+ EulerAngle - One EulerAngle update.
+subscribe_attitude_angular_velocity_body()
+AttitudeAngularVelocityBodyHandle mavsdk::Telemetry::subscribe_attitude_angular_velocity_body(const AttitudeAngularVelocityBodyCallback &callback)
+
+Subscribe to 'attitude' updates (angular velocity)
+Parameters
+
+Returns
+ AttitudeAngularVelocityBodyHandle -
+unsubscribe_attitude_angular_velocity_body()
+void mavsdk::Telemetry::unsubscribe_attitude_angular_velocity_body(AttitudeAngularVelocityBodyHandle handle)
+
+Unsubscribe from subscribe_attitude_angular_velocity_body.
+Parameters
+
+attitude_angular_velocity_body()
+AngularVelocityBody mavsdk::Telemetry::attitude_angular_velocity_body() const
+
+Poll for 'AngularVelocityBody' (blocking).
+Returns
+ AngularVelocityBody - One AngularVelocityBody update.
+subscribe_camera_attitude_quaternion()
+CameraAttitudeQuaternionHandle mavsdk::Telemetry::subscribe_camera_attitude_quaternion(const CameraAttitudeQuaternionCallback &callback)
+
+Subscribe to 'camera attitude' updates (quaternion).
+Parameters
+
+Returns
+ CameraAttitudeQuaternionHandle -
+unsubscribe_camera_attitude_quaternion()
+void mavsdk::Telemetry::unsubscribe_camera_attitude_quaternion(CameraAttitudeQuaternionHandle handle)
+
+Unsubscribe from subscribe_camera_attitude_quaternion.
+Parameters
+
+camera_attitude_quaternion()
+Quaternion mavsdk::Telemetry::camera_attitude_quaternion() const
+
+Poll for 'Quaternion' (blocking).
+Returns
+ Quaternion - One Quaternion update.
+subscribe_camera_attitude_euler()
+CameraAttitudeEulerHandle mavsdk::Telemetry::subscribe_camera_attitude_euler(const CameraAttitudeEulerCallback &callback)
+
+Subscribe to 'camera attitude' updates (Euler).
+Parameters
+
+Returns
+ CameraAttitudeEulerHandle -
+unsubscribe_camera_attitude_euler()
+void mavsdk::Telemetry::unsubscribe_camera_attitude_euler(CameraAttitudeEulerHandle handle)
+
+Unsubscribe from subscribe_camera_attitude_euler.
+Parameters
+
+camera_attitude_euler()
+EulerAngle mavsdk::Telemetry::camera_attitude_euler() const
+
+Poll for 'EulerAngle' (blocking).
+Returns
+ EulerAngle - One EulerAngle update.
+subscribe_velocity_ned()
+VelocityNedHandle mavsdk::Telemetry::subscribe_velocity_ned(const VelocityNedCallback &callback)
+
+Subscribe to 'ground speed' updates (NED).
+Parameters
+
+Returns
+ VelocityNedHandle -
+unsubscribe_velocity_ned()
+void mavsdk::Telemetry::unsubscribe_velocity_ned(VelocityNedHandle handle)
+
+Unsubscribe from subscribe_velocity_ned.
+Parameters
+
+velocity_ned()
+VelocityNed mavsdk::Telemetry::velocity_ned() const
+
+Poll for 'VelocityNed' (blocking).
+Returns
+ VelocityNed - One VelocityNed update.
+subscribe_gps_info()
+GpsInfoHandle mavsdk::Telemetry::subscribe_gps_info(const GpsInfoCallback &callback)
+
+Subscribe to 'GPS info' updates.
+Parameters
+
+Returns
+ GpsInfoHandle -
+unsubscribe_gps_info()
+void mavsdk::Telemetry::unsubscribe_gps_info(GpsInfoHandle handle)
+
+Unsubscribe from subscribe_gps_info.
+Parameters
+
+gps_info()
+GpsInfo mavsdk::Telemetry::gps_info() const
+
+Poll for 'GpsInfo' (blocking).
+Returns
+ GpsInfo - One GpsInfo update.
+subscribe_raw_gps()
+RawGpsHandle mavsdk::Telemetry::subscribe_raw_gps(const RawGpsCallback &callback)
+
+Subscribe to 'Raw GPS' updates.
+Parameters
+
+Returns
+ RawGpsHandle -
+unsubscribe_raw_gps()
+void mavsdk::Telemetry::unsubscribe_raw_gps(RawGpsHandle handle)
+
+Unsubscribe from subscribe_raw_gps.
+Parameters
+
+raw_gps()
+RawGps mavsdk::Telemetry::raw_gps() const
+
+Poll for 'RawGps' (blocking).
+Returns
+ RawGps - One RawGps update.
+subscribe_battery()
+BatteryHandle mavsdk::Telemetry::subscribe_battery(const BatteryCallback &callback)
+
+Subscribe to 'battery' updates.
+Parameters
+
+Returns
+ BatteryHandle -
+unsubscribe_battery()
+void mavsdk::Telemetry::unsubscribe_battery(BatteryHandle handle)
+
+Unsubscribe from subscribe_battery.
+Parameters
+
+battery()
+Battery mavsdk::Telemetry::battery() const
+
+Poll for 'Battery' (blocking).
+Returns
+ Battery - One Battery update.
+subscribe_flight_mode()
+FlightModeHandle mavsdk::Telemetry::subscribe_flight_mode(const FlightModeCallback &callback)
+
+Subscribe to 'flight mode' updates.
+Parameters
+
+Returns
+ FlightModeHandle -
+unsubscribe_flight_mode()
+void mavsdk::Telemetry::unsubscribe_flight_mode(FlightModeHandle handle)
+
+Unsubscribe from subscribe_flight_mode.
+Parameters
+
+flight_mode()
+FlightMode mavsdk::Telemetry::flight_mode() const
+
+Poll for 'FlightMode' (blocking).
+Returns
+ FlightMode - One FlightMode update.
+subscribe_health()
+HealthHandle mavsdk::Telemetry::subscribe_health(const HealthCallback &callback)
+
+Subscribe to 'health' updates.
+Parameters
+
+Returns
+ HealthHandle -
+unsubscribe_health()
+void mavsdk::Telemetry::unsubscribe_health(HealthHandle handle)
+
+Unsubscribe from subscribe_health.
+Parameters
+
+health()
+Health mavsdk::Telemetry::health() const
+
+Poll for 'Health' (blocking).
+Returns
+ Health - One Health update.
+subscribe_rc_status()
+RcStatusHandle mavsdk::Telemetry::subscribe_rc_status(const RcStatusCallback &callback)
+
+Subscribe to 'RC status' updates.
+Parameters
+
+Returns
+ RcStatusHandle -
+unsubscribe_rc_status()
+void mavsdk::Telemetry::unsubscribe_rc_status(RcStatusHandle handle)
+
+Unsubscribe from subscribe_rc_status.
+Parameters
+
+rc_status()
+RcStatus mavsdk::Telemetry::rc_status() const
+
+Poll for 'RcStatus' (blocking).
+Returns
+ RcStatus - One RcStatus update.
+subscribe_status_text()
+StatusTextHandle mavsdk::Telemetry::subscribe_status_text(const StatusTextCallback &callback)
+
+Subscribe to 'status text' updates.
+Parameters
+
+Returns
+ StatusTextHandle -
+unsubscribe_status_text()
+void mavsdk::Telemetry::unsubscribe_status_text(StatusTextHandle handle)
+
+Unsubscribe from subscribe_status_text.
+Parameters
+
+status_text()
+StatusText mavsdk::Telemetry::status_text() const
+
+Poll for 'StatusText' (blocking).
+Returns
+ StatusText - One StatusText update.
+subscribe_actuator_control_target()
+ActuatorControlTargetHandle mavsdk::Telemetry::subscribe_actuator_control_target(const ActuatorControlTargetCallback &callback)
+
+Subscribe to 'actuator control target' updates.
+Parameters
+
+Returns
+ ActuatorControlTargetHandle -
+unsubscribe_actuator_control_target()
+void mavsdk::Telemetry::unsubscribe_actuator_control_target(ActuatorControlTargetHandle handle)
+
+Unsubscribe from subscribe_actuator_control_target.
+Parameters
+
+actuator_control_target()
+ActuatorControlTarget mavsdk::Telemetry::actuator_control_target() const
+
+Poll for 'ActuatorControlTarget' (blocking).
+Returns
+ ActuatorControlTarget - One ActuatorControlTarget update.
+subscribe_actuator_output_status()
+ActuatorOutputStatusHandle mavsdk::Telemetry::subscribe_actuator_output_status(const ActuatorOutputStatusCallback &callback)
+
+Subscribe to 'actuator output status' updates.
+Parameters
+
+Returns
+ ActuatorOutputStatusHandle -
+unsubscribe_actuator_output_status()
+void mavsdk::Telemetry::unsubscribe_actuator_output_status(ActuatorOutputStatusHandle handle)
+
+Unsubscribe from subscribe_actuator_output_status.
+Parameters
+
+actuator_output_status()
+ActuatorOutputStatus mavsdk::Telemetry::actuator_output_status() const
+
+Poll for 'ActuatorOutputStatus' (blocking).
+Returns
+ ActuatorOutputStatus - One ActuatorOutputStatus update.
+subscribe_odometry()
+OdometryHandle mavsdk::Telemetry::subscribe_odometry(const OdometryCallback &callback)
+
+Subscribe to 'odometry' updates.
+Parameters
+
+Returns
+ OdometryHandle -
+unsubscribe_odometry()
+void mavsdk::Telemetry::unsubscribe_odometry(OdometryHandle handle)
+
+Unsubscribe from subscribe_odometry.
+Parameters
+
+odometry()
+Odometry mavsdk::Telemetry::odometry() const
+
+Poll for 'Odometry' (blocking).
+Returns
+ Odometry - One Odometry update.
+subscribe_position_velocity_ned()
+PositionVelocityNedHandle mavsdk::Telemetry::subscribe_position_velocity_ned(const PositionVelocityNedCallback &callback)
+
+Subscribe to 'position velocity' updates.
+Parameters
+
+Returns
+ PositionVelocityNedHandle -
+unsubscribe_position_velocity_ned()
+void mavsdk::Telemetry::unsubscribe_position_velocity_ned(PositionVelocityNedHandle handle)
+
+Unsubscribe from subscribe_position_velocity_ned.
+Parameters
+
+position_velocity_ned()
+PositionVelocityNed mavsdk::Telemetry::position_velocity_ned() const
+
+Poll for 'PositionVelocityNed' (blocking).
+Returns
+ PositionVelocityNed - One PositionVelocityNed update.
+subscribe_ground_truth()
+GroundTruthHandle mavsdk::Telemetry::subscribe_ground_truth(const GroundTruthCallback &callback)
+
+Subscribe to 'ground truth' updates.
+Parameters
+
+Returns
+ GroundTruthHandle -
+unsubscribe_ground_truth()
+void mavsdk::Telemetry::unsubscribe_ground_truth(GroundTruthHandle handle)
+
+Unsubscribe from subscribe_ground_truth.
+Parameters
+
+ground_truth()
+GroundTruth mavsdk::Telemetry::ground_truth() const
+
+Poll for 'GroundTruth' (blocking).
+Returns
+ GroundTruth - One GroundTruth update.
+subscribe_fixedwing_metrics()
+FixedwingMetricsHandle mavsdk::Telemetry::subscribe_fixedwing_metrics(const FixedwingMetricsCallback &callback)
+
+Subscribe to 'fixedwing metrics' updates.
+Parameters
+
+Returns
+ FixedwingMetricsHandle -
+unsubscribe_fixedwing_metrics()
+void mavsdk::Telemetry::unsubscribe_fixedwing_metrics(FixedwingMetricsHandle handle)
+
+Unsubscribe from subscribe_fixedwing_metrics.
+Parameters
+
+fixedwing_metrics()
+FixedwingMetrics mavsdk::Telemetry::fixedwing_metrics() const
+
+Poll for 'FixedwingMetrics' (blocking).
+Returns
+ FixedwingMetrics - One FixedwingMetrics update.
+subscribe_imu()
+ImuHandle mavsdk::Telemetry::subscribe_imu(const ImuCallback &callback)
+
+Subscribe to 'IMU' updates (in SI units in NED body frame).
+Parameters
+
+Returns
+ ImuHandle -
+unsubscribe_imu()
+void mavsdk::Telemetry::unsubscribe_imu(ImuHandle handle)
+
+Unsubscribe from subscribe_imu.
+Parameters
+
+imu()
+Imu mavsdk::Telemetry::imu() const
+
+Poll for 'Imu' (blocking).
+Returns
+ Imu - One Imu update.
+subscribe_scaled_imu()
+ScaledImuHandle mavsdk::Telemetry::subscribe_scaled_imu(const ScaledImuCallback &callback)
+
+Subscribe to 'Scaled IMU' updates.
+Parameters
+
+Returns
+ ScaledImuHandle -
+unsubscribe_scaled_imu()
+void mavsdk::Telemetry::unsubscribe_scaled_imu(ScaledImuHandle handle)
+
+Unsubscribe from subscribe_scaled_imu.
+Parameters
+
+scaled_imu()
+Imu mavsdk::Telemetry::scaled_imu() const
+
+Poll for 'Imu' (blocking).
+Returns
+ Imu - One Imu update.
+subscribe_raw_imu()
+RawImuHandle mavsdk::Telemetry::subscribe_raw_imu(const RawImuCallback &callback)
+
+Subscribe to 'Raw IMU' updates.
+Parameters
+
+Returns
+ RawImuHandle -
+unsubscribe_raw_imu()
+void mavsdk::Telemetry::unsubscribe_raw_imu(RawImuHandle handle)
+
+Unsubscribe from subscribe_raw_imu.
+Parameters
+
+raw_imu()
+Imu mavsdk::Telemetry::raw_imu() const
+
+Poll for 'Imu' (blocking).
+Returns
+ Imu - One Imu update.
+subscribe_health_all_ok()
+HealthAllOkHandle mavsdk::Telemetry::subscribe_health_all_ok(const HealthAllOkCallback &callback)
+
+Subscribe to 'HealthAllOk' updates.
+Parameters
+
+Returns
+ HealthAllOkHandle -
+unsubscribe_health_all_ok()
+void mavsdk::Telemetry::unsubscribe_health_all_ok(HealthAllOkHandle handle)
+
+Unsubscribe from subscribe_health_all_ok.
+Parameters
+
+health_all_ok()
+bool mavsdk::Telemetry::health_all_ok() const
+
+Poll for 'bool' (blocking).
+Returns
+ bool - One bool update.
+subscribe_unix_epoch_time()
+UnixEpochTimeHandle mavsdk::Telemetry::subscribe_unix_epoch_time(const UnixEpochTimeCallback &callback)
+
+Subscribe to 'unix epoch time' updates.
+Parameters
+
+Returns
+ UnixEpochTimeHandle -
+unsubscribe_unix_epoch_time()
+void mavsdk::Telemetry::unsubscribe_unix_epoch_time(UnixEpochTimeHandle handle)
+
+Unsubscribe from subscribe_unix_epoch_time.
+Parameters
+
+unix_epoch_time()
+uint64_t mavsdk::Telemetry::unix_epoch_time() const
+
+Poll for 'uint64_t' (blocking).
+Returns
+ uint64_t - One uint64_t update.
+subscribe_distance_sensor()
+DistanceSensorHandle mavsdk::Telemetry::subscribe_distance_sensor(const DistanceSensorCallback &callback)
+
+Subscribe to 'Distance Sensor' updates.
+Parameters
+
+Returns
+ DistanceSensorHandle -
+unsubscribe_distance_sensor()
+void mavsdk::Telemetry::unsubscribe_distance_sensor(DistanceSensorHandle handle)
+
+Unsubscribe from subscribe_distance_sensor.
+Parameters
+
+distance_sensor()
+DistanceSensor mavsdk::Telemetry::distance_sensor() const
+
+Poll for 'DistanceSensor' (blocking).
+Returns
+ DistanceSensor - One DistanceSensor update.
+subscribe_scaled_pressure()
+ScaledPressureHandle mavsdk::Telemetry::subscribe_scaled_pressure(const ScaledPressureCallback &callback)
+
+Subscribe to 'Scaled Pressure' updates.
+Parameters
+
+Returns
+ ScaledPressureHandle -
+unsubscribe_scaled_pressure()
+void mavsdk::Telemetry::unsubscribe_scaled_pressure(ScaledPressureHandle handle)
+
+Unsubscribe from subscribe_scaled_pressure.
+Parameters
+
+scaled_pressure()
+ScaledPressure mavsdk::Telemetry::scaled_pressure() const
+
+Poll for 'ScaledPressure' (blocking).
+Returns
+ ScaledPressure - One ScaledPressure update.
+subscribe_heading()
+HeadingHandle mavsdk::Telemetry::subscribe_heading(const HeadingCallback &callback)
+
+Subscribe to 'Heading' updates.
+Parameters
+
+Returns
+ HeadingHandle -
+unsubscribe_heading()
+void mavsdk::Telemetry::unsubscribe_heading(HeadingHandle handle)
+
+Unsubscribe from subscribe_heading.
+Parameters
+
+heading()
+Heading mavsdk::Telemetry::heading() const
+
+Poll for 'Heading' (blocking).
+Returns
+ Heading - One Heading update.
+subscribe_altitude()
+AltitudeHandle mavsdk::Telemetry::subscribe_altitude(const AltitudeCallback &callback)
+
+Subscribe to 'Altitude' updates.
+Parameters
+
+Returns
+ AltitudeHandle -
+unsubscribe_altitude()
+void mavsdk::Telemetry::unsubscribe_altitude(AltitudeHandle handle)
+
+Unsubscribe from subscribe_altitude.
+Parameters
+
+altitude()
+Altitude mavsdk::Telemetry::altitude() const
+
+Poll for 'Altitude' (blocking).
+Returns
+ Altitude - One Altitude update.
+set_rate_position_async()
+void mavsdk::Telemetry::set_rate_position_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'position' updates.
+This function is non-blocking. See 'set_rate_position' for the blocking counterpart.
+Parameters
+
+set_rate_position()
+Result mavsdk::Telemetry::set_rate_position(double rate_hz) const
+
+Set rate to 'position' updates.
+This function is blocking. See 'set_rate_position_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_home_async()
+void mavsdk::Telemetry::set_rate_home_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'home position' updates.
+This function is non-blocking. See 'set_rate_home' for the blocking counterpart.
+Parameters
+
+set_rate_home()
+Result mavsdk::Telemetry::set_rate_home(double rate_hz) const
+
+Set rate to 'home position' updates.
+This function is blocking. See 'set_rate_home_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_in_air_async()
+void mavsdk::Telemetry::set_rate_in_air_async(double rate_hz, const ResultCallback callback)
+
+Set rate to in-air updates.
+This function is non-blocking. See 'set_rate_in_air' for the blocking counterpart.
+Parameters
+
+set_rate_in_air()
+Result mavsdk::Telemetry::set_rate_in_air(double rate_hz) const
+
+Set rate to in-air updates.
+This function is blocking. See 'set_rate_in_air_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_landed_state_async()
+void mavsdk::Telemetry::set_rate_landed_state_async(double rate_hz, const ResultCallback callback)
+
+Set rate to landed state updates.
+This function is non-blocking. See 'set_rate_landed_state' for the blocking counterpart.
+Parameters
+
+set_rate_landed_state()
+Result mavsdk::Telemetry::set_rate_landed_state(double rate_hz) const
+
+Set rate to landed state updates.
+This function is blocking. See 'set_rate_landed_state_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_vtol_state_async()
+void mavsdk::Telemetry::set_rate_vtol_state_async(double rate_hz, const ResultCallback callback)
+
+Set rate to VTOL state updates.
+This function is non-blocking. See 'set_rate_vtol_state' for the blocking counterpart.
+Parameters
+
+set_rate_vtol_state()
+Result mavsdk::Telemetry::set_rate_vtol_state(double rate_hz) const
+
+Set rate to VTOL state updates.
+This function is blocking. See 'set_rate_vtol_state_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_attitude_quaternion_async()
+void mavsdk::Telemetry::set_rate_attitude_quaternion_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'attitude euler angle' updates.
+This function is non-blocking. See 'set_rate_attitude_quaternion' for the blocking counterpart.
+Parameters
+
+set_rate_attitude_quaternion()
+Result mavsdk::Telemetry::set_rate_attitude_quaternion(double rate_hz) const
+
+Set rate to 'attitude euler angle' updates.
+This function is blocking. See 'set_rate_attitude_quaternion_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_attitude_euler_async()
+void mavsdk::Telemetry::set_rate_attitude_euler_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'attitude quaternion' updates.
+This function is non-blocking. See 'set_rate_attitude_euler' for the blocking counterpart.
+Parameters
+
+set_rate_attitude_euler()
+Result mavsdk::Telemetry::set_rate_attitude_euler(double rate_hz) const
+
+Set rate to 'attitude quaternion' updates.
+This function is blocking. See 'set_rate_attitude_euler_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_camera_attitude_async()
+void mavsdk::Telemetry::set_rate_camera_attitude_async(double rate_hz, const ResultCallback callback)
+
+Set rate of camera attitude updates.
+This function is non-blocking. See 'set_rate_camera_attitude' for the blocking counterpart.
+Parameters
+
+set_rate_camera_attitude()
+Result mavsdk::Telemetry::set_rate_camera_attitude(double rate_hz) const
+
+Set rate of camera attitude updates.
+This function is blocking. See 'set_rate_camera_attitude_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_velocity_ned_async()
+void mavsdk::Telemetry::set_rate_velocity_ned_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'ground speed' updates (NED).
+This function is non-blocking. See 'set_rate_velocity_ned' for the blocking counterpart.
+Parameters
+
+set_rate_velocity_ned()
+Result mavsdk::Telemetry::set_rate_velocity_ned(double rate_hz) const
+
+Set rate to 'ground speed' updates (NED).
+This function is blocking. See 'set_rate_velocity_ned_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_gps_info_async()
+void mavsdk::Telemetry::set_rate_gps_info_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'GPS info' updates.
+This function is non-blocking. See 'set_rate_gps_info' for the blocking counterpart.
+Parameters
+
+set_rate_gps_info()
+Result mavsdk::Telemetry::set_rate_gps_info(double rate_hz) const
+
+Set rate to 'GPS info' updates.
+This function is blocking. See 'set_rate_gps_info_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_battery_async()
+void mavsdk::Telemetry::set_rate_battery_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'battery' updates.
+This function is non-blocking. See 'set_rate_battery' for the blocking counterpart.
+Parameters
+
+set_rate_battery()
+Result mavsdk::Telemetry::set_rate_battery(double rate_hz) const
+
+Set rate to 'battery' updates.
+This function is blocking. See 'set_rate_battery_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_rc_status_async()
+void mavsdk::Telemetry::set_rate_rc_status_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'RC status' updates.
+This function is non-blocking. See 'set_rate_rc_status' for the blocking counterpart.
+Parameters
+
+set_rate_rc_status()
+Result mavsdk::Telemetry::set_rate_rc_status(double rate_hz) const
+
+Set rate to 'RC status' updates.
+This function is blocking. See 'set_rate_rc_status_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_actuator_control_target_async()
+void mavsdk::Telemetry::set_rate_actuator_control_target_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'actuator control target' updates.
+This function is non-blocking. See 'set_rate_actuator_control_target' for the blocking counterpart.
+Parameters
+
+set_rate_actuator_control_target()
+Result mavsdk::Telemetry::set_rate_actuator_control_target(double rate_hz) const
+
+Set rate to 'actuator control target' updates.
+This function is blocking. See 'set_rate_actuator_control_target_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_actuator_output_status_async()
+void mavsdk::Telemetry::set_rate_actuator_output_status_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'actuator output status' updates.
+This function is non-blocking. See 'set_rate_actuator_output_status' for the blocking counterpart.
+Parameters
+
+set_rate_actuator_output_status()
+Result mavsdk::Telemetry::set_rate_actuator_output_status(double rate_hz) const
+
+Set rate to 'actuator output status' updates.
+This function is blocking. See 'set_rate_actuator_output_status_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_odometry_async()
+void mavsdk::Telemetry::set_rate_odometry_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'odometry' updates.
+This function is non-blocking. See 'set_rate_odometry' for the blocking counterpart.
+Parameters
+
+set_rate_odometry()
+Result mavsdk::Telemetry::set_rate_odometry(double rate_hz) const
+
+Set rate to 'odometry' updates.
+This function is blocking. See 'set_rate_odometry_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_position_velocity_ned_async()
+void mavsdk::Telemetry::set_rate_position_velocity_ned_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'position velocity' updates.
+This function is non-blocking. See 'set_rate_position_velocity_ned' for the blocking counterpart.
+Parameters
+
+set_rate_position_velocity_ned()
+Result mavsdk::Telemetry::set_rate_position_velocity_ned(double rate_hz) const
+
+Set rate to 'position velocity' updates.
+This function is blocking. See 'set_rate_position_velocity_ned_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_ground_truth_async()
+void mavsdk::Telemetry::set_rate_ground_truth_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'ground truth' updates.
+This function is non-blocking. See 'set_rate_ground_truth' for the blocking counterpart.
+Parameters
+
+set_rate_ground_truth()
+Result mavsdk::Telemetry::set_rate_ground_truth(double rate_hz) const
+
+Set rate to 'ground truth' updates.
+This function is blocking. See 'set_rate_ground_truth_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_fixedwing_metrics_async()
+void mavsdk::Telemetry::set_rate_fixedwing_metrics_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'fixedwing metrics' updates.
+This function is non-blocking. See 'set_rate_fixedwing_metrics' for the blocking counterpart.
+Parameters
+
+set_rate_fixedwing_metrics()
+Result mavsdk::Telemetry::set_rate_fixedwing_metrics(double rate_hz) const
+
+Set rate to 'fixedwing metrics' updates.
+This function is blocking. See 'set_rate_fixedwing_metrics_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_imu_async()
+void mavsdk::Telemetry::set_rate_imu_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'IMU' updates.
+This function is non-blocking. See 'set_rate_imu' for the blocking counterpart.
+Parameters
+
+set_rate_imu()
+Result mavsdk::Telemetry::set_rate_imu(double rate_hz) const
+
+Set rate to 'IMU' updates.
+This function is blocking. See 'set_rate_imu_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_scaled_imu_async()
+void mavsdk::Telemetry::set_rate_scaled_imu_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'Scaled IMU' updates.
+This function is non-blocking. See 'set_rate_scaled_imu' for the blocking counterpart.
+Parameters
+
+set_rate_scaled_imu()
+Result mavsdk::Telemetry::set_rate_scaled_imu(double rate_hz) const
+
+Set rate to 'Scaled IMU' updates.
+This function is blocking. See 'set_rate_scaled_imu_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_raw_imu_async()
+void mavsdk::Telemetry::set_rate_raw_imu_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'Raw IMU' updates.
+This function is non-blocking. See 'set_rate_raw_imu' for the blocking counterpart.
+Parameters
+
+set_rate_raw_imu()
+Result mavsdk::Telemetry::set_rate_raw_imu(double rate_hz) const
+
+Set rate to 'Raw IMU' updates.
+This function is blocking. See 'set_rate_raw_imu_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_unix_epoch_time_async()
+void mavsdk::Telemetry::set_rate_unix_epoch_time_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'unix epoch time' updates.
+This function is non-blocking. See 'set_rate_unix_epoch_time' for the blocking counterpart.
+Parameters
+
+set_rate_unix_epoch_time()
+Result mavsdk::Telemetry::set_rate_unix_epoch_time(double rate_hz) const
+
+Set rate to 'unix epoch time' updates.
+This function is blocking. See 'set_rate_unix_epoch_time_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_distance_sensor_async()
+void mavsdk::Telemetry::set_rate_distance_sensor_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'Distance Sensor' updates.
+This function is non-blocking. See 'set_rate_distance_sensor' for the blocking counterpart.
+Parameters
+
+set_rate_distance_sensor()
+Result mavsdk::Telemetry::set_rate_distance_sensor(double rate_hz) const
+
+Set rate to 'Distance Sensor' updates.
+This function is blocking. See 'set_rate_distance_sensor_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+set_rate_altitude_async()
+void mavsdk::Telemetry::set_rate_altitude_async(double rate_hz, const ResultCallback callback)
+
+Set rate to 'Altitude' updates.
+This function is non-blocking. See 'set_rate_altitude' for the blocking counterpart.
+Parameters
+
+set_rate_altitude()
+Result mavsdk::Telemetry::set_rate_altitude(double rate_hz) const
+
+Set rate to 'Altitude' updates.
+This function is blocking. See 'set_rate_altitude_async' for the non-blocking counterpart.
+Parameters
+
+Returns
+ Result - Result of request.
+get_gps_global_origin_async()
+void mavsdk::Telemetry::get_gps_global_origin_async(const GetGpsGlobalOriginCallback callback)
+
+Get the GPS location of where the estimator has been initialized.
+This function is non-blocking. See 'get_gps_global_origin' for the blocking counterpart.
+Parameters
+
+get_gps_global_origin()
+std::pair<Result, Telemetry::GpsGlobalOrigin> mavsdk::Telemetry::get_gps_global_origin() const
+
+Get the GPS location of where the estimator has been initialized.
+This function is blocking. See 'get_gps_global_origin_async' for the non-blocking counterpart.
+Returns
+ std::pair< Result, Telemetry::GpsGlobalOrigin > - Result of request.
+operator=()
+const Telemetry& mavsdk::Telemetry::operator=(const Telemetry &)=delete
+
+Equality operator (object is not copyable).
+Parameters
+
+Returns
+ const Telemetry & -
+
+
+