@@ -99,7 +99,7 @@ uint8_t AP_RCTelemetry::run_wfq_scheduler(const bool use_shaper)
99
99
float delay = 0 ;
100
100
bool packet_ready = false ;
101
101
102
- // build message queue for sensor_status_flags
102
+ // build message queue for unhealthy_sensors()
103
103
check_sensor_status_flags ();
104
104
// build message queue for ekf_status
105
105
check_ekf_status ();
@@ -187,13 +187,13 @@ void AP_RCTelemetry::queue_message(MAV_SEVERITY severity, const char *text)
187
187
}
188
188
189
189
/*
190
- * add sensor_status_flags information to message cue, normally passed as sys_status mavlink messages to the GCS, for transmission through FrSky link
190
+ * add unhealthy_sensors() information to message cue, normally passed as sys_status mavlink messages to the GCS, for transmission through FrSky link
191
191
*/
192
192
void AP_RCTelemetry::check_sensor_status_flags (void )
193
193
{
194
194
uint32_t now = AP_HAL::millis ();
195
195
196
- const uint32_t _sensor_status_flags = sensor_status_flags ();
196
+ const uint32_t _sensor_status_flags = unhealthy_sensors ();
197
197
198
198
if ((now - check_sensor_status_timer) >= 5000 ) { // prevent repeating any system_status messages unless 5 seconds have passed
199
199
// only one error is reported at a time (in order of preference). Same setup and displayed messages as Mission Planner.
@@ -279,7 +279,9 @@ void AP_RCTelemetry::check_ekf_status(void)
279
279
}
280
280
}
281
281
282
- uint32_t AP_RCTelemetry::sensor_status_flags () const
282
+ // returns a bitmask of sensors which are present and enabled but also
283
+ // not healthy
284
+ uint32_t AP_RCTelemetry::unhealthy_sensors () const
283
285
{
284
286
uint32_t present;
285
287
uint32_t enabled;
0 commit comments