1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 08:45:36 +03:00

Beginning of the great GPS unfucking.

* Proper initialization sequence framework for various supported GPS types. NMEA will now auto-detect its baud rate based on received frames.
* As a result of the above, gps_baudrate has been changed to enum, to only allow fixed rates. (GPS baudrate, -1: autodetect (NMEA only), 0: 115200, 1: 57600, 2: 38400, 3: 19200, 4: 9600)
* UBX binary initialization at any specified baudrate with auto-reconnect on signal loss.
* GPS thread to handle initialization, signal loss and configuration. No longer does GPS need to be powered before FC, and on GPS reconnect, it will be re-initialized if needed.
MTK NMEA/binary initialization is omitted for now, as I can't find my MTK GPS
GPS deltaTime can be calculated to display update rate.


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@438 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-10-13 15:25:45 +00:00
parent 04560808e7
commit 30ded7ff04
8 changed files with 209 additions and 126 deletions

View file

@ -45,8 +45,6 @@ uint16_t GPS_altitude, GPS_speed; // altitude in 0.1m and speed in 0.1m/s
uint8_t GPS_update = 0; // it's a binary toogle to distinct a GPS position update
int16_t GPS_angle[2] = { 0, 0 }; // it's the angles that must be applied for GPS correction
uint16_t GPS_ground_course = 0; // degrees * 10
uint8_t GPS_Present = 0; // Checksum from Gps serial
uint8_t GPS_Enable = 0;
int16_t nav[2];
int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother
int8_t nav_mode = NAV_MODE_NONE; // Navigation mode
@ -777,9 +775,16 @@ void loop(void)
taskOrder++;
#ifdef BARO
if (sensors(SENSOR_BARO) && getEstimatedAltitude())
break;
break;
#endif
case 3:
// if GPS feature is enabled, gpsThread() will be called at some intervals to check for stuck
// hardware, wrong baud rates, init GPS if needed, etc. Don't use SENSOR_GPS here as gpsThread() can and will
// change this based on available hardware
if (feature(FEATURE_GPS))
gpsThread();
break;
case 4:
taskOrder++;
#ifdef SONAR
if (sensors(SENSOR_SONAR)) {