mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: change always true condition to a timer
This commit is contained in:
parent
08cbf18958
commit
54380bd144
@ -105,11 +105,12 @@ void Copter::esc_calibration_passthrough()
|
||||
BoardConfig.init_safety();
|
||||
|
||||
// wait for safety switch to be pressed
|
||||
uint32_t tstart = AP_HAL::millis();
|
||||
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
bool printed_msg = false;
|
||||
if (!printed_msg) {
|
||||
const uint32_t tnow = AP_HAL::millis();
|
||||
if (tnow - tstart >= 5000) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
|
||||
printed_msg = true;
|
||||
tstart = tnow;
|
||||
}
|
||||
esc_calibration_notify();
|
||||
hal.scheduler->delay(3);
|
||||
@ -161,11 +162,12 @@ void Copter::esc_calibration_auto()
|
||||
BoardConfig.init_safety();
|
||||
|
||||
// wait for safety switch to be pressed
|
||||
uint32_t tstart = AP_HAL::millis();
|
||||
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
bool printed_msg = false;
|
||||
if (!printed_msg) {
|
||||
const uint32_t tnow = AP_HAL::millis();
|
||||
if (tnow - tstart >= 5000) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
|
||||
printed_msg = true;
|
||||
tstart = tnow;
|
||||
}
|
||||
esc_calibration_notify();
|
||||
hal.scheduler->delay(3);
|
||||
|
Loading…
Reference in New Issue
Block a user