diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index b5c69f6dfe..d1201d8c09 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -214,9 +214,9 @@ static void update_crosstrack(void) } } -static long cross_track_test() +static int32_t cross_track_test() { - long temp = target_bearing - original_target_bearing; + int32_t temp = target_bearing - original_target_bearing; temp = wrap_180(temp); return abs(temp); } diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 355c9e1075..c13d29e7ce 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -64,6 +64,9 @@ def get_bearing(loc1, loc2): def current_location(mav): '''return current location''' + # ensure we have a position + mav.recv_match(type='VFR_HUD', blocking=True) + mav.recv_match(type='GPS_RAW', blocking=True) return location(mav.messages['GPS_RAW'].lat, mav.messages['GPS_RAW'].lon, mav.messages['VFR_HUD'].alt) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 3f834ebdb1..4353aff36a 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -42,7 +42,7 @@ def dump_logs(atype): mavproxy.expect("Log]") for i in range(numlogs): mavproxy.send("dump %u\n" % (i+1)) - mavproxy.expect("logs enabled:") + mavproxy.expect("logs enabled:", timeout=120) mavproxy.expect("Log]") util.pexpect_close(mavproxy) util.pexpect_close(sil) diff --git a/libraries/Desktop/support/main.cpp b/libraries/Desktop/support/main.cpp index b380cfda7e..d18d17c712 100644 --- a/libraries/Desktop/support/main.cpp +++ b/libraries/Desktop/support/main.cpp @@ -51,9 +51,6 @@ int main(int argc, char * const argv[]) } signal(SIGALRM, sig_alarm); - if (!desktop_state.slider) { - alarm(5); - } // run main setup() function from sketch setup();