forked from Archive/PX4-Autopilot
Voted sensors: Better error messages
This commit is contained in:
parent
f69a6af989
commit
c31e31bf5e
|
@ -946,9 +946,9 @@ bool VotedSensorsUpdate::check_failover(SensorData &sensor, const char *sensor_n
|
||||||
failover_index,
|
failover_index,
|
||||||
((flags & DataValidator::ERROR_FLAG_NO_DATA) ? " OFF" : ""),
|
((flags & DataValidator::ERROR_FLAG_NO_DATA) ? " OFF" : ""),
|
||||||
((flags & DataValidator::ERROR_FLAG_STALE_DATA) ? " STALE" : ""),
|
((flags & DataValidator::ERROR_FLAG_STALE_DATA) ? " STALE" : ""),
|
||||||
((flags & DataValidator::ERROR_FLAG_TIMEOUT) ? " TOUT" : ""),
|
((flags & DataValidator::ERROR_FLAG_TIMEOUT) ? " TIMEOUT" : ""),
|
||||||
((flags & DataValidator::ERROR_FLAG_HIGH_ERRCOUNT) ? " ECNT" : ""),
|
((flags & DataValidator::ERROR_FLAG_HIGH_ERRCOUNT) ? " ERR CNT" : ""),
|
||||||
((flags & DataValidator::ERROR_FLAG_HIGH_ERRDENSITY) ? " EDNST" : ""));
|
((flags & DataValidator::ERROR_FLAG_HIGH_ERRDENSITY) ? " ERR DNST" : ""));
|
||||||
|
|
||||||
// reduce priority of failed sensor to the minimum
|
// reduce priority of failed sensor to the minimum
|
||||||
sensor.priority[failover_index] = 1;
|
sensor.priority[failover_index] = 1;
|
||||||
|
|
Loading…
Reference in New Issue