From c8a83e17d03ca312f7557b989104f964af2fd4fe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Jul 2013 11:15:48 +1000 Subject: [PATCH] Plane: remove old AIR_START code this was never used or tested --- ArduPlane/ArduPlane.pde | 11 +---------- ArduPlane/commands.pde | 14 -------------- ArduPlane/config.h | 7 ------- ArduPlane/system.pde | 40 +++------------------------------------- 4 files changed, 4 insertions(+), 68 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index c9be5eb24a..7f89e9ebf8 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1022,16 +1022,7 @@ static void update_GPS(void) ground_start_count = 5; } else { - if(ENABLE_AIR_START == 1 && (ground_start_avg / 5) < SPEEDFILT) { - startup_ground(); - - if (g.log_bitmask & MASK_LOG_CMD) - Log_Write_Startup(TYPE_GROUNDSTART_MSG); - - init_home(); - } else if (ENABLE_AIR_START == 0) { - init_home(); - } + init_home(); if (g.compass_enabled) { // Set compass declination automatically diff --git a/ArduPlane/commands.pde b/ArduPlane/commands.pde index 957e483ecd..2e3923818b 100644 --- a/ArduPlane/commands.pde +++ b/ArduPlane/commands.pde @@ -32,13 +32,6 @@ static void update_auto() } } -// this is only used by an air-start -static void reload_commands_airstart() -{ - init_commands(); - decrement_cmd_index(); -} - /* fetch a mission item from EEPROM */ @@ -127,13 +120,6 @@ static void set_cmd_with_index(struct Location temp, int16_t i) hal.storage->write_dword(mem, temp.lng); } -static void decrement_cmd_index() -{ - if (g.command_index > 0) { - g.command_index.set_and_save(g.command_index - 1); - } -} - static int32_t read_alt_to_hold() { if (g.RTL_altitude_cm < 0) { diff --git a/ArduPlane/config.h b/ArduPlane/config.h index b2f9929444..c15bcd2448 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -351,13 +351,6 @@ # define GROUND_START_DELAY 0 #endif -////////////////////////////////////////////////////////////////////////////// -// ENABLE_AIR_START -// -#ifndef ENABLE_AIR_START - # define ENABLE_AIR_START DISABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // ENABLE ELEVON_MIXING // diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 9d3ad31062..4fd240eb0c 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -216,43 +216,9 @@ static void init_ardupilot() hal.uartC->println_P(msg); #endif - if (ENABLE_AIR_START == 1) { - // Perform an air start and get back to flying - gcs_send_text_P(SEVERITY_LOW,PSTR(" AIR START")); - - // Get necessary data from EEPROM - //---------------- - //read_EEPROM_airstart_critical(); - ahrs.init(); - ahrs.set_fly_forward(true); - ahrs.set_wind_estimation(true); - - ins.init(AP_InertialSensor::WARM_START, - ins_sample_rate, - flash_leds); - - // This delay is important for the APM_RC library to work. - // We need some time for the comm between the 328 and 1280 to be established. - int old_pulse = 0; - while (millis()<=1000 - && (abs(old_pulse - hal.rcin->read(g.flight_mode_channel)) > 5 - || hal.rcin->read(g.flight_mode_channel) == 1000 - || hal.rcin->read(g.flight_mode_channel) == 1200)) - { - old_pulse = hal.rcin->read(g.flight_mode_channel); - delay(25); - } - g_gps->update(); - - if (g.log_bitmask & MASK_LOG_CMD) - Log_Write_Startup(TYPE_AIRSTART_MSG); - reload_commands_airstart(); // Get set to resume AUTO from where we left off - - }else { - startup_ground(); - if (g.log_bitmask & MASK_LOG_CMD) - Log_Write_Startup(TYPE_GROUNDSTART_MSG); - } + startup_ground(); + if (g.log_bitmask & MASK_LOG_CMD) + Log_Write_Startup(TYPE_GROUNDSTART_MSG); // choose the nav controller set_nav_controller();