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 AngularVelocityBody

struct AngularVelocityFrd

struct Battery

struct Covariance

struct DistanceSensor

struct EulerAngle

struct FixedwingMetrics

struct GpsInfo

struct GroundTruth

struct Health

struct Imu

struct MagneticFieldFrd

struct Odometry

struct Position

struct PositionBody

struct PositionNed

struct PositionVelocityNed

struct Quaternion

struct RcStatus

struct StatusText

struct VelocityBody

struct VelocityNed

Public Types

Type Description
enum FixType GPS fix type.
enum FlightMode Flight modes.
enum StatusTextType Status types.
enum LandedState Landed State enumeration.
enum Result Possible results returned for telemetry requests.
std::function< void(Result)> ResultCallback Callback type for asynchronous Telemetry calls.
std::function< void(Position)> PositionCallback Callback type for subscribe_position.
std::function< void(Position)> HomeCallback Callback type for subscribe_home.
std::function< void(bool)> InAirCallback Callback type for subscribe_in_air.
std::function< void(LandedState)> LandedStateCallback Callback type for subscribe_landed_state.
std::function< void(bool)> ArmedCallback Callback type for subscribe_armed.
std::function< void(Quaternion)> AttitudeQuaternionCallback Callback type for subscribe_attitude_quaternion.
std::function< void(EulerAngle)> AttitudeEulerCallback Callback type for subscribe_attitude_euler.
std::function< void(AngularVelocityBody)> AttitudeAngularVelocityBodyCallback Callback type for subscribe_attitude_angular_velocity_body.
std::function< void(Quaternion)> CameraAttitudeQuaternionCallback Callback type for subscribe_camera_attitude_quaternion.
std::function< void(EulerAngle)> CameraAttitudeEulerCallback Callback type for subscribe_camera_attitude_euler.
std::function< void(VelocityNed)> VelocityNedCallback Callback type for subscribe_velocity_ned.
std::function< void(GpsInfo)> GpsInfoCallback Callback type for subscribe_gps_info.
std::function< void(Battery)> BatteryCallback Callback type for subscribe_battery.
std::function< void(FlightMode)> FlightModeCallback Callback type for subscribe_flight_mode.
std::function< void(Health)> HealthCallback Callback type for subscribe_health.
std::function< void(RcStatus)> RcStatusCallback Callback type for subscribe_rc_status.
std::function< void(StatusText)> StatusTextCallback Callback type for subscribe_status_text.
std::function< void(ActuatorControlTarget)> ActuatorControlTargetCallback Callback type for subscribe_actuator_control_target.
std::function< void(ActuatorOutputStatus)> ActuatorOutputStatusCallback Callback type for subscribe_actuator_output_status.
std::function< void(Odometry)> OdometryCallback Callback type for subscribe_odometry.
std::function< void(PositionVelocityNed)> PositionVelocityNedCallback Callback type for subscribe_position_velocity_ned.
std::function< void(GroundTruth)> GroundTruthCallback Callback type for subscribe_ground_truth.
std::function< void(FixedwingMetrics)> FixedwingMetricsCallback Callback type for subscribe_fixedwing_metrics.
std::function< void(Imu)> ImuCallback Callback type for subscribe_imu.
std::function< void(bool)> HealthAllOkCallback Callback type for subscribe_health_all_ok.
std::function< void(uint64_t)> UnixEpochTimeCallback Callback type for subscribe_unix_epoch_time.
std::function< void(DistanceSensor)> DistanceSensorCallback Callback type for subscribe_distance_sensor.

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 () Destructor (internal use only).
  Telemetry (const Telemetry & other) Copy constructor.
void subscribe_position (PositionCallback callback) Subscribe to 'position' updates.
Position position () const Poll for 'Position' (blocking).
void subscribe_home (HomeCallback callback) Subscribe to 'home position' updates.
Position home () const Poll for 'Position' (blocking).
void subscribe_in_air (InAirCallback callback) Subscribe to in-air updates.
bool in_air () const Poll for 'bool' (blocking).
void subscribe_landed_state (LandedStateCallback callback) Subscribe to landed state updates.
LandedState landed_state () const Poll for 'LandedState' (blocking).
void subscribe_armed (ArmedCallback callback) Subscribe to armed updates.
bool armed () const Poll for 'bool' (blocking).
void subscribe_attitude_quaternion (AttitudeQuaternionCallback callback) Subscribe to 'attitude' updates (quaternion).
Quaternion attitude_quaternion () const Poll for 'Quaternion' (blocking).
void subscribe_attitude_euler (AttitudeEulerCallback callback) Subscribe to 'attitude' updates (Euler).
EulerAngle attitude_euler () const Poll for 'EulerAngle' (blocking).
void subscribe_attitude_angular_velocity_body (AttitudeAngularVelocityBodyCallback callback) Subscribe to 'attitude' updates (angular velocity)
AngularVelocityBody attitude_angular_velocity_body () const Poll for 'AngularVelocityBody' (blocking).
void subscribe_camera_attitude_quaternion (CameraAttitudeQuaternionCallback callback) Subscribe to 'camera attitude' updates (quaternion).
Quaternion camera_attitude_quaternion () const Poll for 'Quaternion' (blocking).
void subscribe_camera_attitude_euler (CameraAttitudeEulerCallback callback) Subscribe to 'camera attitude' updates (Euler).
EulerAngle camera_attitude_euler () const Poll for 'EulerAngle' (blocking).
void subscribe_velocity_ned (VelocityNedCallback callback) Subscribe to 'ground speed' updates (NED).
VelocityNed velocity_ned () const Poll for 'VelocityNed' (blocking).
void subscribe_gps_info (GpsInfoCallback callback) Subscribe to 'GPS info' updates.
GpsInfo gps_info () const Poll for 'GpsInfo' (blocking).
void subscribe_battery (BatteryCallback callback) Subscribe to 'battery' updates.
Battery battery () const Poll for 'Battery' (blocking).
void subscribe_flight_mode (FlightModeCallback callback) Subscribe to 'flight mode' updates.
FlightMode flight_mode () const Poll for 'FlightMode' (blocking).
void subscribe_health (HealthCallback callback) Subscribe to 'health' updates.
Health health () const Poll for 'Health' (blocking).
void subscribe_rc_status (RcStatusCallback callback) Subscribe to 'RC status' updates.
RcStatus rc_status () const Poll for 'RcStatus' (blocking).
void subscribe_status_text (StatusTextCallback callback) Subscribe to 'status text' updates.
StatusText status_text () const Poll for 'StatusText' (blocking).
void subscribe_actuator_control_target (ActuatorControlTargetCallback callback) Subscribe to 'actuator control target' updates.
ActuatorControlTarget actuator_control_target () const Poll for 'ActuatorControlTarget' (blocking).
void subscribe_actuator_output_status (ActuatorOutputStatusCallback callback) Subscribe to 'actuator output status' updates.
ActuatorOutputStatus actuator_output_status () const Poll for 'ActuatorOutputStatus' (blocking).
void subscribe_odometry (OdometryCallback callback) Subscribe to 'odometry' updates.
Odometry odometry () const Poll for 'Odometry' (blocking).
void subscribe_position_velocity_ned (PositionVelocityNedCallback callback) Subscribe to 'position velocity' updates.
PositionVelocityNed position_velocity_ned () const Poll for 'PositionVelocityNed' (blocking).
void subscribe_ground_truth (GroundTruthCallback callback) Subscribe to 'ground truth' updates.
GroundTruth ground_truth () const Poll for 'GroundTruth' (blocking).
void subscribe_fixedwing_metrics (FixedwingMetricsCallback callback) Subscribe to 'fixedwing metrics' updates.
FixedwingMetrics fixedwing_metrics () const Poll for 'FixedwingMetrics' (blocking).
void subscribe_imu (ImuCallback callback) Subscribe to 'IMU' updates.
Imu imu () const Poll for 'Imu' (blocking).
void subscribe_health_all_ok (HealthAllOkCallback callback) Subscribe to 'HealthAllOk' updates.
bool health_all_ok () const Poll for 'bool' (blocking).
void subscribe_unix_epoch_time (UnixEpochTimeCallback callback) Subscribe to 'unix epoch time' updates.
uint64_t unix_epoch_time () const Poll for 'uint64_t' (blocking).
void subscribe_distance_sensor (DistanceSensorCallback callback) Subscribe to 'Distance Sensor' updates.
DistanceSensor distance_sensor () const Poll for 'DistanceSensor' (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_attitude_async (double rate_hz, const ResultCallback callback) Set rate to 'attitude' updates.
Result set_rate_attitude (double rate_hz)const Set rate to 'attitude' 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_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.
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()

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 HomeCallback

using mavsdk::Telemetry::HomeCallback =  std::function<void(Position)>

Callback type for subscribe_home.

typedef InAirCallback

using mavsdk::Telemetry::InAirCallback =  std::function<void(bool)>

Callback type for subscribe_in_air.

typedef LandedStateCallback

using mavsdk::Telemetry::LandedStateCallback =  std::function<void(LandedState)>

Callback type for subscribe_landed_state.

typedef ArmedCallback

using mavsdk::Telemetry::ArmedCallback =  std::function<void(bool)>

Callback type for subscribe_armed.

typedef AttitudeQuaternionCallback

using mavsdk::Telemetry::AttitudeQuaternionCallback =  std::function<void(Quaternion)>

Callback type for subscribe_attitude_quaternion.

typedef AttitudeEulerCallback

using mavsdk::Telemetry::AttitudeEulerCallback =  std::function<void(EulerAngle)>

Callback type for subscribe_attitude_euler.

typedef AttitudeAngularVelocityBodyCallback

using mavsdk::Telemetry::AttitudeAngularVelocityBodyCallback =  std::function<void(AngularVelocityBody)>

Callback 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 CameraAttitudeEulerCallback

using mavsdk::Telemetry::CameraAttitudeEulerCallback =  std::function<void(EulerAngle)>

Callback type for subscribe_camera_attitude_euler.

typedef VelocityNedCallback

using mavsdk::Telemetry::VelocityNedCallback =  std::function<void(VelocityNed)>

Callback type for subscribe_velocity_ned.

typedef GpsInfoCallback

using mavsdk::Telemetry::GpsInfoCallback =  std::function<void(GpsInfo)>

Callback type for subscribe_gps_info.

typedef BatteryCallback

using mavsdk::Telemetry::BatteryCallback =  std::function<void(Battery)>

Callback type for subscribe_battery.

typedef FlightModeCallback

using mavsdk::Telemetry::FlightModeCallback =  std::function<void(FlightMode)>

Callback type for subscribe_flight_mode.

typedef HealthCallback

using mavsdk::Telemetry::HealthCallback =  std::function<void(Health)>

Callback type for subscribe_health.

typedef RcStatusCallback

using mavsdk::Telemetry::RcStatusCallback =  std::function<void(RcStatus)>

Callback type for subscribe_rc_status.

typedef StatusTextCallback

using mavsdk::Telemetry::StatusTextCallback =  std::function<void(StatusText)>

Callback type for subscribe_status_text.

typedef ActuatorControlTargetCallback

using mavsdk::Telemetry::ActuatorControlTargetCallback =  std::function<void(ActuatorControlTarget)>

Callback type for subscribe_actuator_control_target.

typedef ActuatorOutputStatusCallback

using mavsdk::Telemetry::ActuatorOutputStatusCallback =  std::function<void(ActuatorOutputStatus)>

Callback type for subscribe_actuator_output_status.

typedef OdometryCallback

using mavsdk::Telemetry::OdometryCallback =  std::function<void(Odometry)>

Callback type for subscribe_odometry.

typedef PositionVelocityNedCallback

using mavsdk::Telemetry::PositionVelocityNedCallback =  std::function<void(PositionVelocityNed)>

Callback type for subscribe_position_velocity_ned.

typedef GroundTruthCallback

using mavsdk::Telemetry::GroundTruthCallback =  std::function<void(GroundTruth)>

Callback type for subscribe_ground_truth.

typedef FixedwingMetricsCallback

using mavsdk::Telemetry::FixedwingMetricsCallback =  std::function<void(FixedwingMetrics)>

Callback type for subscribe_fixedwing_metrics.

typedef ImuCallback

using mavsdk::Telemetry::ImuCallback =  std::function<void(Imu)>

Callback type for subscribe_imu.

typedef HealthAllOkCallback

using mavsdk::Telemetry::HealthAllOkCallback =  std::function<void(bool)>

Callback 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 DistanceSensorCallback

using mavsdk::Telemetry::DistanceSensorCallback =  std::function<void(DistanceSensor)>

Callback type for subscribe_distance_sensor.

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 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.

Member Function Documentation

subscribe_position()

void mavsdk::Telemetry::subscribe_position(PositionCallback callback)

Subscribe to 'position' updates.

Parameters

position()

Position mavsdk::Telemetry::position() const

Poll for 'Position' (blocking).

Returns

Position - One Position update.

subscribe_home()

void mavsdk::Telemetry::subscribe_home(HomeCallback callback)

Subscribe to 'home position' updates.

Parameters

home()

Position mavsdk::Telemetry::home() const

Poll for 'Position' (blocking).

Returns

Position - One Position update.

subscribe_in_air()

void mavsdk::Telemetry::subscribe_in_air(InAirCallback callback)

Subscribe to in-air updates.

Parameters

in_air()

bool mavsdk::Telemetry::in_air() const

Poll for 'bool' (blocking).

Returns

 bool - One bool update.

subscribe_landed_state()

void mavsdk::Telemetry::subscribe_landed_state(LandedStateCallback callback)

Subscribe to landed state updates.

Parameters

landed_state()

LandedState mavsdk::Telemetry::landed_state() const

Poll for 'LandedState' (blocking).

Returns

LandedState - One LandedState update.

subscribe_armed()

void mavsdk::Telemetry::subscribe_armed(ArmedCallback callback)

Subscribe to armed updates.

Parameters

armed()

bool mavsdk::Telemetry::armed() const

Poll for 'bool' (blocking).

Returns

 bool - One bool update.

subscribe_attitude_quaternion()

void mavsdk::Telemetry::subscribe_attitude_quaternion(AttitudeQuaternionCallback callback)

Subscribe to 'attitude' updates (quaternion).

Parameters

attitude_quaternion()

Quaternion mavsdk::Telemetry::attitude_quaternion() const

Poll for 'Quaternion' (blocking).

Returns

Quaternion - One Quaternion update.

subscribe_attitude_euler()

void mavsdk::Telemetry::subscribe_attitude_euler(AttitudeEulerCallback callback)

Subscribe to 'attitude' updates (Euler).

Parameters

attitude_euler()

EulerAngle mavsdk::Telemetry::attitude_euler() const

Poll for 'EulerAngle' (blocking).

Returns

EulerAngle - One EulerAngle update.

subscribe_attitude_angular_velocity_body()

void mavsdk::Telemetry::subscribe_attitude_angular_velocity_body(AttitudeAngularVelocityBodyCallback callback)

Subscribe to 'attitude' updates (angular velocity)

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()

void mavsdk::Telemetry::subscribe_camera_attitude_quaternion(CameraAttitudeQuaternionCallback callback)

Subscribe to 'camera attitude' updates (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()

void mavsdk::Telemetry::subscribe_camera_attitude_euler(CameraAttitudeEulerCallback callback)

Subscribe to 'camera attitude' updates (Euler).

Parameters

camera_attitude_euler()

EulerAngle mavsdk::Telemetry::camera_attitude_euler() const

Poll for 'EulerAngle' (blocking).

Returns

EulerAngle - One EulerAngle update.

subscribe_velocity_ned()

void mavsdk::Telemetry::subscribe_velocity_ned(VelocityNedCallback callback)

Subscribe to 'ground speed' updates (NED).

Parameters

velocity_ned()

VelocityNed mavsdk::Telemetry::velocity_ned() const

Poll for 'VelocityNed' (blocking).

Returns

VelocityNed - One VelocityNed update.

subscribe_gps_info()

void mavsdk::Telemetry::subscribe_gps_info(GpsInfoCallback callback)

Subscribe to 'GPS info' updates.

Parameters

gps_info()

GpsInfo mavsdk::Telemetry::gps_info() const

Poll for 'GpsInfo' (blocking).

Returns

GpsInfo - One GpsInfo update.

subscribe_battery()

void mavsdk::Telemetry::subscribe_battery(BatteryCallback callback)

Subscribe to 'battery' updates.

Parameters

battery()

Battery mavsdk::Telemetry::battery() const

Poll for 'Battery' (blocking).

Returns

Battery - One Battery update.

subscribe_flight_mode()

void mavsdk::Telemetry::subscribe_flight_mode(FlightModeCallback callback)

Subscribe to 'flight mode' updates.

Parameters

flight_mode()

FlightMode mavsdk::Telemetry::flight_mode() const

Poll for 'FlightMode' (blocking).

Returns

FlightMode - One FlightMode update.

subscribe_health()

void mavsdk::Telemetry::subscribe_health(HealthCallback callback)

Subscribe to 'health' updates.

Parameters

health()

Health mavsdk::Telemetry::health() const

Poll for 'Health' (blocking).

Returns

Health - One Health update.

subscribe_rc_status()

void mavsdk::Telemetry::subscribe_rc_status(RcStatusCallback callback)

Subscribe to 'RC status' updates.

Parameters

rc_status()

RcStatus mavsdk::Telemetry::rc_status() const

Poll for 'RcStatus' (blocking).

Returns

RcStatus - One RcStatus update.

subscribe_status_text()

void mavsdk::Telemetry::subscribe_status_text(StatusTextCallback callback)

Subscribe to 'status text' updates.

Parameters

status_text()

StatusText mavsdk::Telemetry::status_text() const

Poll for 'StatusText' (blocking).

Returns

StatusText - One StatusText update.

subscribe_actuator_control_target()

void mavsdk::Telemetry::subscribe_actuator_control_target(ActuatorControlTargetCallback callback)

Subscribe to 'actuator control target' updates.

Parameters

actuator_control_target()

ActuatorControlTarget mavsdk::Telemetry::actuator_control_target() const

Poll for 'ActuatorControlTarget' (blocking).

Returns

ActuatorControlTarget - One ActuatorControlTarget update.

subscribe_actuator_output_status()

void mavsdk::Telemetry::subscribe_actuator_output_status(ActuatorOutputStatusCallback callback)

Subscribe to 'actuator output status' updates.

Parameters

actuator_output_status()

ActuatorOutputStatus mavsdk::Telemetry::actuator_output_status() const

Poll for 'ActuatorOutputStatus' (blocking).

Returns

ActuatorOutputStatus - One ActuatorOutputStatus update.

subscribe_odometry()

void mavsdk::Telemetry::subscribe_odometry(OdometryCallback callback)

Subscribe to 'odometry' updates.

Parameters

odometry()

Odometry mavsdk::Telemetry::odometry() const

Poll for 'Odometry' (blocking).

Returns

Odometry - One Odometry update.

subscribe_position_velocity_ned()

void mavsdk::Telemetry::subscribe_position_velocity_ned(PositionVelocityNedCallback callback)

Subscribe to 'position velocity' updates.

Parameters

position_velocity_ned()

PositionVelocityNed mavsdk::Telemetry::position_velocity_ned() const

Poll for 'PositionVelocityNed' (blocking).

Returns

PositionVelocityNed - One PositionVelocityNed update.

subscribe_ground_truth()

void mavsdk::Telemetry::subscribe_ground_truth(GroundTruthCallback callback)

Subscribe to 'ground truth' updates.

Parameters

ground_truth()

GroundTruth mavsdk::Telemetry::ground_truth() const

Poll for 'GroundTruth' (blocking).

Returns

GroundTruth - One GroundTruth update.

subscribe_fixedwing_metrics()

void mavsdk::Telemetry::subscribe_fixedwing_metrics(FixedwingMetricsCallback callback)

Subscribe to 'fixedwing metrics' updates.

Parameters

fixedwing_metrics()

FixedwingMetrics mavsdk::Telemetry::fixedwing_metrics() const

Poll for 'FixedwingMetrics' (blocking).

Returns

FixedwingMetrics - One FixedwingMetrics update.

subscribe_imu()

void mavsdk::Telemetry::subscribe_imu(ImuCallback callback)

Subscribe to 'IMU' updates.

Parameters

imu()

Imu mavsdk::Telemetry::imu() const

Poll for 'Imu' (blocking).

Returns

Imu - One Imu update.

subscribe_health_all_ok()

void mavsdk::Telemetry::subscribe_health_all_ok(HealthAllOkCallback callback)

Subscribe to 'HealthAllOk' updates.

Parameters

health_all_ok()

bool mavsdk::Telemetry::health_all_ok() const

Poll for 'bool' (blocking).

Returns

 bool - One bool update.

subscribe_unix_epoch_time()

void mavsdk::Telemetry::subscribe_unix_epoch_time(UnixEpochTimeCallback callback)

Subscribe to 'unix epoch time' updates.

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()

void mavsdk::Telemetry::subscribe_distance_sensor(DistanceSensorCallback callback)

Subscribe to 'Distance Sensor' updates.

Parameters

distance_sensor()

DistanceSensor mavsdk::Telemetry::distance_sensor() const

Poll for 'DistanceSensor' (blocking).

Returns

DistanceSensor - One DistanceSensor 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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

Returns

Result - Result of request.

set_rate_attitude_async()

void mavsdk::Telemetry::set_rate_attitude_async(double rate_hz, const ResultCallback callback)

Set rate to 'attitude' updates.

This function is non-blocking. See 'set_rate_attitude' for the blocking counterpart.

Parameters

set_rate_attitude()

Result mavsdk::Telemetry::set_rate_attitude(double rate_hz) const

Set rate to 'attitude' updates.

This function is blocking. See 'set_rate_attitude_async' for the non-blocking counterpart.

Parameters

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

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

  • double rate_hz -

Returns

Result - Result of request.

operator=()

const Telemetry& mavsdk::Telemetry::operator=(const Telemetry &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const Telemetry & -

© Dronecode 2017-2020. License: CC BY 4.0            Updated: 2021-02-08 13:41:53

results matching ""

    No results matching ""