Browse Source

Plane: remove old AIR_START code

this was never used or tested
master
Andrew Tridgell 12 years ago
parent
commit
c8a83e17d0
  1. 11
      ArduPlane/ArduPlane.pde
  2. 14
      ArduPlane/commands.pde
  3. 7
      ArduPlane/config.h
  4. 40
      ArduPlane/system.pde

11
ArduPlane/ArduPlane.pde

@ -1022,16 +1022,7 @@ static void update_GPS(void) @@ -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

14
ArduPlane/commands.pde

@ -32,13 +32,6 @@ static void update_auto() @@ -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) @@ -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) {

7
ArduPlane/config.h

@ -351,13 +351,6 @@ @@ -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
//

40
ArduPlane/system.pde

@ -216,43 +216,9 @@ static void init_ardupilot() @@ -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("<init_ardupilot> 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();

Loading…
Cancel
Save