mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_PosControl: emit mavlink warning instead of internal error
This commit is contained in:
parent
2ebd317585
commit
80c87f3d48
@ -615,7 +615,7 @@ void AC_PosControl::update_xy_controller()
|
||||
init_xy_controller();
|
||||
if (has_good_timing()) {
|
||||
// call internal error because initialisation has not been done
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Bad loop slippage detected.");
|
||||
}
|
||||
}
|
||||
_last_update_xy_us = AP_HAL::micros64();
|
||||
@ -962,7 +962,7 @@ void AC_PosControl::update_z_controller()
|
||||
init_z_controller();
|
||||
if (has_good_timing()) {
|
||||
// call internal error because initialisation has not been done
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Bad loop slippage detected.");
|
||||
}
|
||||
}
|
||||
_last_update_z_us = AP_HAL::micros64();
|
||||
|
Loading…
Reference in New Issue
Block a user