PX4 Firmware
PX4 Autopilot Software http://px4.io
MavlinkStreamHighLatency2 Class Reference

#include <mavlink_high_latency2.h>

Inheritance diagram for MavlinkStreamHighLatency2:
Collaboration diagram for MavlinkStreamHighLatency2:

Classes

struct  PerBatteryData
 

Public Member Functions

const char * get_name () const
 
uint16_t get_id ()
 
unsigned get_size ()
 Get maximal total messages size on update. More...
 
bool const_rate ()
 
- Public Member Functions inherited from ListNode< MavlinkStream *>
void setSibling (MavlinkStream * sibling)
 
const MavlinkStreamgetSibling () const
 

Static Public Member Functions

static const char * get_name_static ()
 
static uint16_t get_id_static ()
 
static MavlinkStreamnew_instance (Mavlink *mavlink)
 

Protected Member Functions

 MavlinkStreamHighLatency2 (Mavlink *mavlink)
 
bool send (const hrt_abstime t)
 
void reset_analysers (const hrt_abstime t)
 
bool write_airspeed (mavlink_high_latency2_t *msg)
 
bool write_attitude_sp (mavlink_high_latency2_t *msg)
 
bool write_battery_status (mavlink_high_latency2_t *msg)
 
bool write_estimator_status (mavlink_high_latency2_t *msg)
 
bool write_fw_ctrl_status (mavlink_high_latency2_t *msg)
 
bool write_geofence_result (mavlink_high_latency2_t *msg)
 
bool write_global_position (mavlink_high_latency2_t *msg)
 
bool write_mission_result (mavlink_high_latency2_t *msg)
 
bool write_tecs_status (mavlink_high_latency2_t *msg)
 
bool write_vehicle_status (mavlink_high_latency2_t *msg)
 
bool write_vehicle_status_flags (mavlink_high_latency2_t *msg)
 
bool write_wind_estimate (mavlink_high_latency2_t *msg)
 
void update_data ()
 Function to collect/update data for the streams at a high rate independant of actual stream rate. More...
 
void update_airspeed ()
 
void update_tecs_status ()
 
void update_battery_status ()
 
void update_global_position ()
 
void update_gps ()
 
void update_vehicle_status ()
 
void update_wind_estimate ()
 
void set_default_values (mavlink_high_latency2_t &msg) const
 

Private Member Functions

 MavlinkStreamHighLatency2 (MavlinkStreamHighLatency2 &)
 
MavlinkStreamHighLatency2operator= (const MavlinkStreamHighLatency2 &)
 

Private Attributes

MavlinkOrbSubscription_actuator_sub_0
 
uint64_t _actuator_time_0
 
MavlinkOrbSubscription_actuator_sub_1
 
uint64_t _actuator_time_1
 
MavlinkOrbSubscription_airspeed_sub
 
uint64_t _airspeed_time
 
MavlinkOrbSubscription_attitude_sp_sub
 
uint64_t _attitude_sp_time
 
MavlinkOrbSubscription_estimator_status_sub
 
uint64_t _estimator_status_time
 
MavlinkOrbSubscription_pos_ctrl_status_sub
 
uint64_t _pos_ctrl_status_time
 
MavlinkOrbSubscription_geofence_sub
 
uint64_t _geofence_time
 
MavlinkOrbSubscription_global_pos_sub
 
uint64_t _global_pos_time
 
MavlinkOrbSubscription_gps_sub
 
uint64_t _gps_time
 
MavlinkOrbSubscription_mission_result_sub
 
uint64_t _mission_result_time
 
MavlinkOrbSubscription_status_sub
 
uint64_t _status_time
 
MavlinkOrbSubscription_status_flags_sub
 
uint64_t _status_flags_time
 
MavlinkOrbSubscription_tecs_status_sub
 
uint64_t _tecs_time
 
MavlinkOrbSubscription_wind_sub
 
uint64_t _wind_time
 
SimpleAnalyzer _airspeed
 
SimpleAnalyzer _airspeed_sp
 
SimpleAnalyzer _climb_rate
 
SimpleAnalyzer _eph
 
SimpleAnalyzer _epv
 
SimpleAnalyzer _groundspeed
 
SimpleAnalyzer _temperature
 
SimpleAnalyzer _throttle
 
SimpleAnalyzer _windspeed
 
hrt_abstime _last_reset_time = 0
 
hrt_abstime _last_update_time = 0
 
float _update_rate_filtered = 0.0f
 
PerBatteryData _batteries [ORB_MULTI_MAX_INSTANCES]
 

Additional Inherited Members

- Protected Attributes inherited from ListNode< MavlinkStream *>
MavlinkStream_list_node_sibling
 

Detailed Description

Definition at line 47 of file mavlink_high_latency2.h.

Constructor & Destructor Documentation

◆ MavlinkStreamHighLatency2() [1/2]

MavlinkStreamHighLatency2::MavlinkStreamHighLatency2 ( MavlinkStreamHighLatency2 )
private

Referenced by new_instance().

Here is the caller graph for this function:

◆ MavlinkStreamHighLatency2() [2/2]

MavlinkStreamHighLatency2::MavlinkStreamHighLatency2 ( Mavlink mavlink)
explicitprotected

Definition at line 64 of file mavlink_high_latency2.cpp.

References _batteries, MavlinkStream::_mavlink, Mavlink::add_orb_subscription(), ORB_ID, ORB_MULTI_MAX_INSTANCES, MavlinkStream::reset_last_sent(), and MavlinkStreamHighLatency2::PerBatteryData::subscription.

Here is the call graph for this function:

Member Function Documentation

◆ const_rate()

bool MavlinkStreamHighLatency2::const_rate ( )
inlinevirtual
Returns
true if steam rate shouldn't be adjusted

Reimplemented from MavlinkStream.

Definition at line 80 of file mavlink_high_latency2.h.

◆ get_id()

uint16_t MavlinkStreamHighLatency2::get_id ( )
inlinevirtual

Implements MavlinkStream.

Definition at line 65 of file mavlink_high_latency2.h.

References get_id_static().

Here is the call graph for this function:

◆ get_id_static()

static uint16_t MavlinkStreamHighLatency2::get_id_static ( )
inlinestatic

Definition at line 60 of file mavlink_high_latency2.h.

Referenced by get_id().

Here is the caller graph for this function:

◆ get_name()

const char* MavlinkStreamHighLatency2::get_name ( ) const
inlinevirtual

Implements MavlinkStream.

Definition at line 50 of file mavlink_high_latency2.h.

References get_name_static().

Here is the call graph for this function:

◆ get_name_static()

static const char* MavlinkStreamHighLatency2::get_name_static ( )
inlinestatic

Definition at line 55 of file mavlink_high_latency2.h.

Referenced by get_name().

Here is the caller graph for this function:

◆ get_size()

unsigned MavlinkStreamHighLatency2::get_size ( )
inlinevirtual

Get maximal total messages size on update.

Implements MavlinkStream.

Definition at line 75 of file mavlink_high_latency2.h.

◆ new_instance()

static MavlinkStream* MavlinkStreamHighLatency2::new_instance ( Mavlink mavlink)
inlinestatic

Definition at line 70 of file mavlink_high_latency2.h.

References MavlinkStreamHighLatency2().

Here is the call graph for this function:

◆ operator=()

MavlinkStreamHighLatency2& MavlinkStreamHighLatency2::operator= ( const MavlinkStreamHighLatency2 )
private

◆ reset_analysers()

void MavlinkStreamHighLatency2::reset_analysers ( const hrt_abstime  t)
protected

Definition at line 227 of file mavlink_high_latency2.cpp.

References _airspeed, _airspeed_sp, _batteries, _climb_rate, _eph, _epv, _groundspeed, _last_reset_time, _temperature, _throttle, _windspeed, MavlinkStreamHighLatency2::PerBatteryData::analyzer, ORB_MULTI_MAX_INSTANCES, and SimpleAnalyzer::reset().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send()

◆ set_default_values()

void MavlinkStreamHighLatency2::set_default_values ( mavlink_high_latency2_t &  msg) const
protected

Definition at line 602 of file mavlink_high_latency2.cpp.

Referenced by send().

Here is the caller graph for this function:

◆ update_airspeed()

void MavlinkStreamHighLatency2::update_airspeed ( )
protected

Definition at line 515 of file mavlink_high_latency2.cpp.

References _airspeed, _airspeed_sub, _temperature, _update_rate_filtered, SimpleAnalyzer::add_value(), airspeed_s::air_temperature_celsius, airspeed_s::indicated_airspeed_m_s, and MavlinkOrbSubscription::update().

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_battery_status()

void MavlinkStreamHighLatency2::update_battery_status ( )
protected

Definition at line 534 of file mavlink_high_latency2.cpp.

References _batteries, _update_rate_filtered, SimpleAnalyzer::add_value(), MavlinkStreamHighLatency2::PerBatteryData::analyzer, battery_status_s::connected, MavlinkStreamHighLatency2::PerBatteryData::connected, ORB_MULTI_MAX_INSTANCES, and battery_status_s::remaining.

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_data()

void MavlinkStreamHighLatency2::update_data ( )
protectedvirtual

Function to collect/update data for the streams at a high rate independant of actual stream rate.

This function is called at every iteration of the mavlink module.

Reimplemented from MavlinkStream.

Definition at line 490 of file mavlink_high_latency2.cpp.

References _last_update_time, _update_rate_filtered, f(), hrt_absolute_time(), hrt_abstime, update_airspeed(), update_battery_status(), update_global_position(), update_gps(), update_tecs_status(), update_vehicle_status(), and update_wind_estimate().

Here is the call graph for this function:

◆ update_global_position()

void MavlinkStreamHighLatency2::update_global_position ( )
protected

Definition at line 546 of file mavlink_high_latency2.cpp.

References _climb_rate, _global_pos_sub, _groundspeed, _update_rate_filtered, SimpleAnalyzer::add_value(), MavlinkOrbSubscription::update(), vehicle_global_position_s::vel_d, vehicle_global_position_s::vel_e, and vehicle_global_position_s::vel_n.

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_gps()

void MavlinkStreamHighLatency2::update_gps ( )
protected

Definition at line 557 of file mavlink_high_latency2.cpp.

References _eph, _epv, _gps_sub, _update_rate_filtered, SimpleAnalyzer::add_value(), vehicle_gps_position_s::eph, vehicle_gps_position_s::epv, gps, and MavlinkOrbSubscription::update().

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_tecs_status()

void MavlinkStreamHighLatency2::update_tecs_status ( )
protected

Definition at line 525 of file mavlink_high_latency2.cpp.

References _airspeed_sp, _tecs_status_sub, _update_rate_filtered, SimpleAnalyzer::add_value(), tecs_status_s::airspeed_sp, and MavlinkOrbSubscription::update().

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_vehicle_status()

void MavlinkStreamHighLatency2::update_vehicle_status ( )
protected

Definition at line 567 of file mavlink_high_latency2.cpp.

References _actuator_sub_0, _actuator_sub_1, _status_sub, _throttle, _update_rate_filtered, SimpleAnalyzer::add_value(), vehicle_status_s::arming_state, actuator_controls_s::control, f(), vehicle_status_s::is_vtol, status, MavlinkOrbSubscription::update(), vehicle_status_s::vehicle_type, and VEHICLE_TYPE_FIXED_WING.

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_wind_estimate()

void MavlinkStreamHighLatency2::update_wind_estimate ( )
protected

Definition at line 592 of file mavlink_high_latency2.cpp.

References _update_rate_filtered, _wind_sub, _windspeed, SimpleAnalyzer::add_value(), MavlinkOrbSubscription::update(), wind_estimate_s::windspeed_east, and wind_estimate_s::windspeed_north.

Referenced by update_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_airspeed()

bool MavlinkStreamHighLatency2::write_airspeed ( mavlink_high_latency2_t *  msg)
protected

Definition at line 248 of file mavlink_high_latency2.cpp.

References _airspeed_sub, _airspeed_time, airspeed_s::confidence, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_attitude_sp()

bool MavlinkStreamHighLatency2::write_attitude_sp ( mavlink_high_latency2_t *  msg)
protected

Definition at line 263 of file mavlink_high_latency2.cpp.

References _attitude_sp_sub, _attitude_sp_time, math::degrees(), MavlinkOrbSubscription::update(), matrix::wrap_2pi(), and vehicle_attitude_setpoint_s::yaw_body.

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_battery_status()

bool MavlinkStreamHighLatency2::write_battery_status ( mavlink_high_latency2_t *  msg)
protected

Definition at line 276 of file mavlink_high_latency2.cpp.

References _batteries, battery_status_s::connected, MavlinkStreamHighLatency2::PerBatteryData::connected, ORB_MULTI_MAX_INSTANCES, MavlinkStreamHighLatency2::PerBatteryData::timestamp, and battery_status_s::warning.

Referenced by send().

Here is the caller graph for this function:

◆ write_estimator_status()

bool MavlinkStreamHighLatency2::write_estimator_status ( mavlink_high_latency2_t *  msg)
protected

Definition at line 295 of file mavlink_high_latency2.cpp.

References _estimator_status_sub, _estimator_status_time, estimator_status_s::filter_fault_flags, estimator_status_s::gps_check_fail_flags, estimator_status_s::innovation_check_flags, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_fw_ctrl_status()

bool MavlinkStreamHighLatency2::write_fw_ctrl_status ( mavlink_high_latency2_t *  msg)
protected

Definition at line 312 of file mavlink_high_latency2.cpp.

References _pos_ctrl_status_sub, _pos_ctrl_status_time, convert_limit_safe(), MavlinkOrbSubscription::update(), and position_controller_status_s::wp_dist.

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_geofence_result()

bool MavlinkStreamHighLatency2::write_geofence_result ( mavlink_high_latency2_t *  msg)
protected

Definition at line 327 of file mavlink_high_latency2.cpp.

References _geofence_sub, _geofence_time, geofence_result_s::geofence_violated, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_global_position()

bool MavlinkStreamHighLatency2::write_global_position ( mavlink_high_latency2_t *  msg)
protected

Definition at line 342 of file mavlink_high_latency2.cpp.

References _global_pos_sub, _global_pos_time, vehicle_global_position_s::alt, convert_limit_safe(), math::degrees(), vehicle_global_position_s::lat, vehicle_global_position_s::lon, MavlinkOrbSubscription::update(), matrix::wrap_2pi(), and vehicle_global_position_s::yaw.

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_mission_result()

bool MavlinkStreamHighLatency2::write_mission_result ( mavlink_high_latency2_t *  msg)
protected

Definition at line 369 of file mavlink_high_latency2.cpp.

References _mission_result_sub, _mission_result_time, mission_result_s::seq_current, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_tecs_status()

bool MavlinkStreamHighLatency2::write_tecs_status ( mavlink_high_latency2_t *  msg)
protected

Definition at line 382 of file mavlink_high_latency2.cpp.

References _tecs_status_sub, _tecs_time, tecs_status_s::altitude_sp, convert_limit_safe(), and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_vehicle_status()

bool MavlinkStreamHighLatency2::write_vehicle_status ( mavlink_high_latency2_t *  msg)
protected

Definition at line 397 of file mavlink_high_latency2.cpp.

References _status_sub, _status_time, px4_custom_mode::custom_mode_hl, vehicle_status_s::engine_failure, get_mavlink_navigation_mode(), vehicle_status_s::mission_failure, vehicle_status_s::onboard_control_sensors_enabled, vehicle_status_s::onboard_control_sensors_health, vehicle_status_s::rc_signal_lost, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_vehicle_status_flags()

bool MavlinkStreamHighLatency2::write_vehicle_status_flags ( mavlink_high_latency2_t *  msg)
protected

Definition at line 457 of file mavlink_high_latency2.cpp.

References _status_flags_sub, _status_flags_time, vehicle_status_flags_s::condition_global_position_valid, vehicle_status_flags_s::offboard_control_signal_found_once, vehicle_status_flags_s::offboard_control_signal_lost, and MavlinkOrbSubscription::update().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_wind_estimate()

bool MavlinkStreamHighLatency2::write_wind_estimate ( mavlink_high_latency2_t *  msg)
protected

Definition at line 476 of file mavlink_high_latency2.cpp.

References _wind_sub, _wind_time, math::degrees(), MavlinkOrbSubscription::update(), wind_estimate_s::windspeed_east, wind_estimate_s::windspeed_north, and matrix::wrap_2pi().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _actuator_sub_0

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_actuator_sub_0
private

Definition at line 95 of file mavlink_high_latency2.h.

Referenced by update_vehicle_status().

◆ _actuator_sub_1

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_actuator_sub_1
private

Definition at line 98 of file mavlink_high_latency2.h.

Referenced by update_vehicle_status().

◆ _actuator_time_0

uint64_t MavlinkStreamHighLatency2::_actuator_time_0
private

Definition at line 96 of file mavlink_high_latency2.h.

◆ _actuator_time_1

uint64_t MavlinkStreamHighLatency2::_actuator_time_1
private

Definition at line 99 of file mavlink_high_latency2.h.

◆ _airspeed

SimpleAnalyzer MavlinkStreamHighLatency2::_airspeed
private

Definition at line 137 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_airspeed().

◆ _airspeed_sp

SimpleAnalyzer MavlinkStreamHighLatency2::_airspeed_sp
private

Definition at line 138 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_tecs_status().

◆ _airspeed_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_airspeed_sub
private

Definition at line 101 of file mavlink_high_latency2.h.

Referenced by update_airspeed(), and write_airspeed().

◆ _airspeed_time

uint64_t MavlinkStreamHighLatency2::_airspeed_time
private

Definition at line 102 of file mavlink_high_latency2.h.

Referenced by write_airspeed().

◆ _attitude_sp_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_attitude_sp_sub
private

Definition at line 104 of file mavlink_high_latency2.h.

Referenced by write_attitude_sp().

◆ _attitude_sp_time

uint64_t MavlinkStreamHighLatency2::_attitude_sp_time
private

Definition at line 105 of file mavlink_high_latency2.h.

Referenced by write_attitude_sp().

◆ _batteries

PerBatteryData MavlinkStreamHighLatency2::_batteries[ORB_MULTI_MAX_INSTANCES]
private

◆ _climb_rate

SimpleAnalyzer MavlinkStreamHighLatency2::_climb_rate
private

Definition at line 139 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_global_position().

◆ _eph

SimpleAnalyzer MavlinkStreamHighLatency2::_eph
private

Definition at line 140 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_gps().

◆ _epv

SimpleAnalyzer MavlinkStreamHighLatency2::_epv
private

Definition at line 141 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_gps().

◆ _estimator_status_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_estimator_status_sub
private

Definition at line 107 of file mavlink_high_latency2.h.

Referenced by write_estimator_status().

◆ _estimator_status_time

uint64_t MavlinkStreamHighLatency2::_estimator_status_time
private

Definition at line 108 of file mavlink_high_latency2.h.

Referenced by write_estimator_status().

◆ _geofence_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_geofence_sub
private

Definition at line 113 of file mavlink_high_latency2.h.

Referenced by write_geofence_result().

◆ _geofence_time

uint64_t MavlinkStreamHighLatency2::_geofence_time
private

Definition at line 114 of file mavlink_high_latency2.h.

Referenced by write_geofence_result().

◆ _global_pos_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_global_pos_sub
private

Definition at line 116 of file mavlink_high_latency2.h.

Referenced by update_global_position(), and write_global_position().

◆ _global_pos_time

uint64_t MavlinkStreamHighLatency2::_global_pos_time
private

Definition at line 117 of file mavlink_high_latency2.h.

Referenced by write_global_position().

◆ _gps_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_gps_sub
private

Definition at line 119 of file mavlink_high_latency2.h.

Referenced by update_gps().

◆ _gps_time

uint64_t MavlinkStreamHighLatency2::_gps_time
private

Definition at line 120 of file mavlink_high_latency2.h.

◆ _groundspeed

SimpleAnalyzer MavlinkStreamHighLatency2::_groundspeed
private

Definition at line 142 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_global_position().

◆ _last_reset_time

hrt_abstime MavlinkStreamHighLatency2::_last_reset_time = 0
private

Definition at line 147 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), and send().

◆ _last_update_time

hrt_abstime MavlinkStreamHighLatency2::_last_update_time = 0
private

Definition at line 148 of file mavlink_high_latency2.h.

Referenced by update_data().

◆ _mission_result_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_mission_result_sub
private

Definition at line 122 of file mavlink_high_latency2.h.

Referenced by write_mission_result().

◆ _mission_result_time

uint64_t MavlinkStreamHighLatency2::_mission_result_time
private

Definition at line 123 of file mavlink_high_latency2.h.

Referenced by write_mission_result().

◆ _pos_ctrl_status_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_pos_ctrl_status_sub
private

Definition at line 110 of file mavlink_high_latency2.h.

Referenced by write_fw_ctrl_status().

◆ _pos_ctrl_status_time

uint64_t MavlinkStreamHighLatency2::_pos_ctrl_status_time
private

Definition at line 111 of file mavlink_high_latency2.h.

Referenced by write_fw_ctrl_status().

◆ _status_flags_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_status_flags_sub
private

Definition at line 128 of file mavlink_high_latency2.h.

Referenced by write_vehicle_status_flags().

◆ _status_flags_time

uint64_t MavlinkStreamHighLatency2::_status_flags_time
private

Definition at line 129 of file mavlink_high_latency2.h.

Referenced by write_vehicle_status_flags().

◆ _status_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_status_sub
private

Definition at line 125 of file mavlink_high_latency2.h.

Referenced by update_vehicle_status(), and write_vehicle_status().

◆ _status_time

uint64_t MavlinkStreamHighLatency2::_status_time
private

Definition at line 126 of file mavlink_high_latency2.h.

Referenced by write_vehicle_status().

◆ _tecs_status_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_tecs_status_sub
private

Definition at line 131 of file mavlink_high_latency2.h.

Referenced by update_tecs_status(), and write_tecs_status().

◆ _tecs_time

uint64_t MavlinkStreamHighLatency2::_tecs_time
private

Definition at line 132 of file mavlink_high_latency2.h.

Referenced by write_tecs_status().

◆ _temperature

SimpleAnalyzer MavlinkStreamHighLatency2::_temperature
private

Definition at line 143 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_airspeed().

◆ _throttle

SimpleAnalyzer MavlinkStreamHighLatency2::_throttle
private

Definition at line 144 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_vehicle_status().

◆ _update_rate_filtered

float MavlinkStreamHighLatency2::_update_rate_filtered = 0.0f
private

◆ _wind_sub

MavlinkOrbSubscription* MavlinkStreamHighLatency2::_wind_sub
private

Definition at line 134 of file mavlink_high_latency2.h.

Referenced by update_wind_estimate(), and write_wind_estimate().

◆ _wind_time

uint64_t MavlinkStreamHighLatency2::_wind_time
private

Definition at line 135 of file mavlink_high_latency2.h.

Referenced by write_wind_estimate().

◆ _windspeed

SimpleAnalyzer MavlinkStreamHighLatency2::_windspeed
private

Definition at line 145 of file mavlink_high_latency2.h.

Referenced by reset_analysers(), send(), and update_wind_estimate().


The documentation for this class was generated from the following files: