mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Added ability to exit the GPS test loop.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1526 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
09df4b35ea
commit
aaa19ebbfc
@ -478,12 +478,18 @@ test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
while(1){
|
||||
delay(100);
|
||||
update_GPS();
|
||||
if(home.lng != 0)
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
|
||||
if(home.lng != 0){
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
delay(100);
|
||||
calc_distance_error();
|
||||
// Blink GPS LED if we don't have a fix
|
||||
// ------------------------------------
|
||||
@ -836,3 +842,13 @@ void print_hit_enter()
|
||||
{
|
||||
Serial.printf_P(PSTR("Hit Enter to exit.\n\n"));
|
||||
}
|
||||
|
||||
|
||||
|
||||
void print_motor_out(){
|
||||
Serial.printf("out: %d %d %d %d\n",
|
||||
(motor_out[RIGHT] - rc_3.radio_min),
|
||||
(motor_out[LEFT] - rc_3.radio_min),
|
||||
(motor_out[FRONT] - rc_3.radio_min),
|
||||
(motor_out[BACK] - rc_3.radio_min));
|
||||
}
|
Loading…
Reference in New Issue
Block a user