esc_calibration: adjust timing to work with all tested ESCs

Some ESCs e.g. Gaui enter the menu relatively quickly if the
signal is high for too long. To solve that it's kept high shorter.
Also all tested ESCs detect the low signal within a shorter time
so no need to wait longer.
This commit is contained in:
Matthias Grob 2023-06-13 15:43:26 +02:00
parent 53bcb8789f
commit ae678e8e2f
1 changed files with 3 additions and 3 deletions

View File

@ -132,7 +132,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub)
break;
}
if ((now - timeout_start) > 10_s) {
if ((now - timeout_start) > 6_s) {
// Timeout, we abort here
calibration_failed = true;
break;
@ -144,7 +144,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub)
// 4 Wait for ESCs to measure high signal
if (!calibration_failed) {
calibration_log_info(mavlink_log_pub, "[cal] Battery connected");
px4_usleep(8_s);
px4_usleep(3_s);
}
// 5 Set motors to low
@ -154,7 +154,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub)
// 6 Wait for ESCs to measure low signal
if (!calibration_failed) {
px4_usleep(8_s);
px4_usleep(5_s);
}
// 7 release control