50 const char *get_name()
const 52 return MavlinkStreamHighLatency2::get_name_static();
55 static const char *get_name_static()
57 return "HIGH_LATENCY2";
60 static uint16_t get_id_static()
62 return MAVLINK_MSG_ID_HIGH_LATENCY2;
67 return get_id_static();
77 return MAVLINK_MSG_ID_HIGH_LATENCY2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
87 uint64_t _actuator_time_0;
90 uint64_t _actuator_time_1;
93 uint64_t _airspeed_time;
96 uint64_t _attitude_sp_time;
99 uint64_t _battery_time;
102 uint64_t _estimator_status_time;
105 uint64_t _pos_ctrl_status_time;
108 uint64_t _geofence_time;
111 uint64_t _global_pos_time;
117 uint64_t _mission_result_time;
120 uint64_t _status_time;
123 uint64_t _status_flags_time;
144 float _update_rate_filtered = 0.0f;
157 bool write_airspeed(mavlink_high_latency2_t *msg);
159 bool write_attitude_sp(mavlink_high_latency2_t *msg);
161 bool write_battery_status(mavlink_high_latency2_t *msg);
163 bool write_estimator_status(mavlink_high_latency2_t *msg);
165 bool write_fw_ctrl_status(mavlink_high_latency2_t *msg);
167 bool write_geofence_result(mavlink_high_latency2_t *msg);
169 bool write_global_position(mavlink_high_latency2_t *msg);
171 bool write_mission_result(mavlink_high_latency2_t *msg);
173 bool write_tecs_status(mavlink_high_latency2_t *msg);
175 bool write_vehicle_status(mavlink_high_latency2_t *msg);
177 bool write_vehicle_status_flags(mavlink_high_latency2_t *msg);
179 bool write_wind_estimate(mavlink_high_latency2_t *msg);
183 void update_airspeed();
185 void update_tecs_status();
187 void update_battery_status();
189 void update_global_position();
193 void update_vehicle_status();
195 void update_wind_estimate();
197 void set_default_values(mavlink_high_latency2_t &msg)
const;
void update_data()
Function to collect/update data for the streams at a high rate independant of actual stream rate...
Definition: mavlink_high_latency2.cpp:459
bool const_rate()
Definition: mavlink_high_latency2.h:80
MAVLink 1.0 message formatters definition.
Definition: mavlink_stream.h:50
SimpleAnalyzer.
Definition: mavlink_simple_analyzer.h:61
MAVLink 2.0 protocol interface definition.
Mavlink messages stream definition.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: mavlink_orb_subscription.h:48
Definition: mavlink_high_latency2.h:47
unsigned get_size()
Get maximal total messages size on update.
Definition: mavlink_high_latency2.h:75