From 9d1fa8cee2238199694e6b5a38d2a34ea3d4626d Mon Sep 17 00:00:00 2001 From: Roman Date: Mon, 2 Jul 2018 13:30:43 +0200 Subject: [PATCH] esc_calibration: adjust timeout when waiting for user to connect battery to 20 seconds Signed-off-by: Roman --- src/modules/commander/esc_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp index 0f3f15049a..9d53f5877c 100644 --- a/src/modules/commander/esc_calibration.cpp +++ b/src/modules/commander/esc_calibration.cpp @@ -99,7 +99,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub, struct actuator_armed_s* a bool batt_updated = false; bool batt_connected = true; // for safety resons assume battery is connected, will be cleared below if not the case - hrt_abstime battery_connect_wait_timeout = 3_s; + hrt_abstime battery_connect_wait_timeout = 20_s; hrt_abstime pwm_high_timeout = 3_s; hrt_abstime timeout_start = 0;