commander: estimator nav test is not an arming check

This commit is contained in:
Daniel Agar 2022-10-24 20:43:28 -04:00 committed by Beat Küng
parent 6f861ba889
commit a7b909234b
1 changed files with 3 additions and 3 deletions

View File

@ -625,9 +625,9 @@ void EstimatorChecks::checkEstimatorStatusFlags(const Context &context, Report &
* @description
* Land and recalibrate the sensors.
*/
reporter.armingCheckFailure(NavModes::All, health_component_t::local_position_estimate,
events::ID("check_estimator_nav_failure"),
events::Log::Emergency, "Navigation failure");
reporter.healthFailure(NavModes::All, health_component_t::local_position_estimate,
events::ID("check_estimator_nav_failure"),
events::Log::Emergency, "Navigation failure");
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Navigation failure! Land and recalibrate sensors\t");