APM: removed the GPS_enabled flag

this fixes using GPS_PROTOCOL to specify a specific GPS with a GPS
that takes a few updates before it works (eg. needing baud rate
changes).

This makes it easier to use an APM1-1280 with more features enabled
This commit is contained in:
Andrew Tridgell 2012-09-11 13:37:25 +10:00
parent c9a299665c
commit 7e672628ea
4 changed files with 8 additions and 27 deletions

View File

@ -399,9 +399,6 @@ static byte ground_start_count = 5;
// on the ground or in the air. Used to decide if a ground start is appropriate if we
// booted with an air start.
static int16_t ground_start_avg;
// Tracks if GPS is enabled based on statup routine
// If we do not detect GPS at startup, we stop trying and assume GPS is not connected
static bool GPS_enabled = false;
// true if we have a position estimate from AHRS
static bool have_position;
@ -844,10 +841,8 @@ static void medium_loop()
//-------------------------------
case 0:
medium_loopCounter++;
if(GPS_enabled) {
update_GPS();
calc_gndspeed_undershoot();
}
update_GPS();
calc_gndspeed_undershoot();
#if HIL_MODE != HIL_MODE_ATTITUDE
if (g.compass_enabled && compass.read()) {

View File

@ -560,7 +560,7 @@ static void do_change_speed()
static void do_set_home()
{
if(next_nonnav_command.p1 == 1 && GPS_enabled) {
if (next_nonnav_command.p1 == 1 && g_gps->status() == GPS::GPS_OK) {
init_home();
} else {
home.id = MAV_CMD_NAV_WAYPOINT;

View File

@ -99,8 +99,11 @@ static void calc_airspeed_errors()
static void calc_gndspeed_undershoot()
{
// Function is overkill, but here in case we want to add filtering later
groundspeed_undershoot = (g.min_gndspeed_cm > 0) ? (g.min_gndspeed_cm - g_gps->ground_speed) : 0;
// Function is overkill, but here in case we want to add filtering
// later
if (g_gps && g_gps->status() == GPS::GPS_OK) {
groundspeed_undershoot = (g.min_gndspeed_cm > 0) ? (g.min_gndspeed_cm - g_gps->ground_speed) : 0;
}
}
static void calc_bearing_error()

View File

@ -249,9 +249,7 @@ static void init_ardupilot()
old_pulse = APM_RC.InputCh(g.flight_mode_channel);
delay(25);
}
GPS_enabled = false;
g_gps->update();
if (g_gps->status() != 0 || HIL_MODE != HIL_MODE_DISABLED) GPS_enabled = true;
if (g.log_bitmask & MASK_LOG_CMD)
Log_Write_Startup(TYPE_AIRSTART_MSG);
@ -306,21 +304,6 @@ static void startup_ground(void)
// -------------------
init_commands();
// Read in the GPS - see if one is connected
GPS_enabled = false;
for (byte counter = 0;; counter++) {
g_gps->update();
if (g_gps->status() != 0 || HIL_MODE != HIL_MODE_DISABLED) {
GPS_enabled = true;
break;
}
if (counter >= 2) {
GPS_enabled = false;
break;
}
}
// Makes the servos wiggle - 3 times signals ready to fly
// -----------------------
demo_servos(3);