mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: remove unused wait_for_yes function
This commit is contained in:
parent
3be100469b
commit
7bf3296425
|
@ -1069,24 +1069,6 @@ print_blanks(int16_t num)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
static bool
|
|
||||||
wait_for_yes()
|
|
||||||
{
|
|
||||||
int c;
|
|
||||||
cliSerial->flush();
|
|
||||||
cliSerial->printf_P(PSTR("Y to save\n"));
|
|
||||||
|
|
||||||
do {
|
|
||||||
c = cliSerial->read();
|
|
||||||
} while (-1 == c);
|
|
||||||
|
|
||||||
if (('y' == c) || ('Y' == c))
|
|
||||||
return true;
|
|
||||||
else
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
static void
|
||||||
print_divider(void)
|
print_divider(void)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue