mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
01a4a120df
@ -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);
|
||||
}
|
||||
|
@ -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)
|
||||
|
@ -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)
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user