Plane: fixed CLI build again

thanks to John Williams for pointing it out
This commit is contained in:
Andrew Tridgell 2014-11-11 21:54:25 +11:00
parent 986b7bf894
commit 8ee677cfce
2 changed files with 29 additions and 29 deletions

View File

@ -183,7 +183,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
uint8_t i;
for(i = 0; i < 100; i++) {
delay(20);
hal.scheduler->delay(20);
read_radio();
}
@ -191,7 +191,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
if(channel_roll->radio_in < 500) {
while(1) {
cliSerial->printf_P(PSTR("\nNo radio; Check connectors."));
delay(1000);
hal.scheduler->delay(1000);
// stop here
}
}
@ -225,7 +225,7 @@ setup_radio(uint8_t argc, const Menu::arg *argv)
cliSerial->printf_P(PSTR("\nMove all controls to each extreme. Hit Enter to save: \n"));
while(1) {
delay(20);
hal.scheduler->delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
read_radio();

View File

@ -85,10 +85,10 @@ static int8_t
test_radio_pwm(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
while(1) {
delay(20);
hal.scheduler->delay(20);
// Filters radio input - adjust filters in the radio.pde file
// ----------------------------------------------------------
@ -115,10 +115,10 @@ static int8_t
test_passthru(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
while(1) {
delay(20);
hal.scheduler->delay(20);
// New radio frame? (we could use also if((millis()- timer) > 20)
if (hal.rcin->new_input()) {
@ -141,14 +141,14 @@ static int8_t
test_radio(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
// read the radio to set trims
// ---------------------------
trim_radio();
while(1) {
delay(20);
hal.scheduler->delay(20);
read_radio();
channel_roll->calc_pwm();
@ -182,7 +182,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
uint8_t fail_test;
print_hit_enter();
for(int16_t i = 0; i < 50; i++) {
delay(20);
hal.scheduler->delay(20);
read_radio();
}
@ -194,12 +194,12 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
cliSerial->printf_P(PSTR("Unplug battery, throttle in neutral, turn off radio.\n"));
while(channel_throttle->control_in > 0) {
delay(20);
hal.scheduler->delay(20);
read_radio();
}
while(1) {
delay(20);
hal.scheduler->delay(20);
read_radio();
if(channel_throttle->control_in > 0) {
@ -235,19 +235,19 @@ static int8_t
test_relay(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
while(1) {
cliSerial->printf_P(PSTR("Relay on\n"));
relay.on(0);
delay(3000);
hal.scheduler->delay(3000);
if(cliSerial->available() > 0) {
return (0);
}
cliSerial->printf_P(PSTR("Relay off\n"));
relay.off(0);
delay(3000);
hal.scheduler->delay(3000);
if(cliSerial->available() > 0) {
return (0);
}
@ -257,7 +257,7 @@ test_relay(uint8_t argc, const Menu::arg *argv)
static int8_t
test_wp(uint8_t argc, const Menu::arg *argv)
{
delay(1000);
hal.scheduler->delay(1000);
// save the alitude above home option
if (g.RTL_altitude_cm < 0) {
@ -297,7 +297,7 @@ static int8_t
test_xbee(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
cliSerial->printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n"));
while(1) {
@ -316,14 +316,14 @@ static int8_t
test_modeswitch(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
cliSerial->printf_P(PSTR("Control CH "));
cliSerial->println(FLIGHT_MODE_CHANNEL, BASE_DEC);
while(1) {
delay(20);
hal.scheduler->delay(20);
uint8_t switchPosition = readSwitch();
if (oldSwitchPosition != switchPosition) {
cliSerial->printf_P(PSTR("Position %d\n"), (int)switchPosition);
@ -366,14 +366,14 @@ test_adc(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
apm1_adc.Init();
delay(1000);
hal.scheduler->delay(1000);
cliSerial->printf_P(PSTR("ADC\n"));
delay(1000);
hal.scheduler->delay(1000);
while(1) {
for (int8_t i=0; i<9; i++) cliSerial->printf_P(PSTR("%.1f\t"),apm1_adc.Ch(i));
cliSerial->println();
delay(100);
hal.scheduler->delay(100);
if(cliSerial->available() > 0) {
return (0);
}
@ -385,11 +385,11 @@ static int8_t
test_gps(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
uint32_t last_message_time_ms = 0;
while(1) {
delay(100);
hal.scheduler->delay(100);
gps.update();
@ -423,12 +423,12 @@ test_ins(uint8_t argc, const Menu::arg *argv)
ahrs.reset();
print_hit_enter();
delay(1000);
hal.scheduler->delay(1000);
uint8_t counter = 0;
while(1) {
delay(20);
hal.scheduler->delay(20);
if (hal.scheduler->micros() - fast_loopTimer_us > 19000UL) {
fast_loopTimer_us = hal.scheduler->micros();
@ -492,7 +492,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
while(1) {
delay(20);
hal.scheduler->delay(20);
if (hal.scheduler->micros() - fast_loopTimer_us > 19000UL) {
fast_loopTimer_us = hal.scheduler->micros();
@ -555,7 +555,7 @@ test_airspeed(uint8_t argc, const Menu::arg *argv)
print_enabled(true);
while(1) {
delay(20);
hal.scheduler->delay(20);
read_airspeed();
cliSerial->printf_P(PSTR("%.1f m/s\n"), airspeed.get_airspeed());
@ -576,7 +576,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
init_barometer();
while(1) {
delay(100);
hal.scheduler->delay(100);
if (!barometer.healthy()) {
cliSerial->println_P(PSTR("not healthy"));