mirror of https://github.com/ArduPilot/ardupilot
Notify: Update for GPS types
This commit is contained in:
parent
d05b0d5885
commit
9346117c01
|
@ -423,7 +423,7 @@ void Display::update_prearm(uint8_t r)
|
|||
|
||||
void Display::update_gps(uint8_t r)
|
||||
{
|
||||
static const char * gpsfixname[] = {"Other", "NoGPS","NoFix","2D ","3D ","DGPS " ,"RTK "};
|
||||
static const char * gpsfixname[] = {"Other", "NoGPS","NoFix","2D ","3D ","DGPS ", "RTK f", "RTK F"};
|
||||
char msg [DISPLAY_MESSAGE_SIZE];
|
||||
const char * fixname;
|
||||
switch (AP_Notify::flags.gps_status) {
|
||||
|
@ -442,9 +442,12 @@ void Display::update_gps(uint8_t r)
|
|||
case AP_GPS::GPS_OK_FIX_3D_DGPS:
|
||||
fixname = gpsfixname[5];
|
||||
break;
|
||||
case AP_GPS::GPS_OK_FIX_3D_RTK:
|
||||
case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT:
|
||||
fixname = gpsfixname[6];
|
||||
break;
|
||||
case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED:
|
||||
fixname = gpsfixname[7];
|
||||
break;
|
||||
default:
|
||||
fixname = gpsfixname[0];
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue