diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index a80f80aa9d..3aed001f79 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -88,6 +88,8 @@ static void zero_airspeed(void) } +#endif // HIL_MODE != HIL_MODE_ATTITUDE + static void init_compass() { compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft @@ -110,8 +112,6 @@ static void init_optflow() #endif } -#endif // HIL_MODE != HIL_MODE_ATTITUDE - static void read_battery(void) { battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9; diff --git a/libraries/AP_GPS/AP_GPS_Auto.cpp b/libraries/AP_GPS/AP_GPS_Auto.cpp index b3a93b8a68..4eaa531a4b 100644 --- a/libraries/AP_GPS/AP_GPS_Auto.cpp +++ b/libraries/AP_GPS/AP_GPS_Auto.cpp @@ -99,6 +99,7 @@ AP_GPS_Auto::_detect(void) unsigned long then; int fingerprint[4]; int tries; + int charcount; GPS *gps; // @@ -114,15 +115,16 @@ AP_GPS_Auto::_detect(void) // XXX We can detect babble by counting incoming characters, but // what would we do about it? // + charcount = 0; _port->flush(); then = millis(); do { - callback(1); if (_port->available()) { then = millis(); _port->read(); + charcount++; } - } while ((millis() - then) < 50); + } while ((millis() - then) < 50 && charcount < 5000); // // Collect four characters to fingerprint a device