AP_GPS: Support more fix types

This commit is contained in:
Michael du Breuil 2016-10-16 17:56:34 -07:00 committed by Francisco Ferreira
parent 9346117c01
commit 1c1e6e9398
13 changed files with 38 additions and 36 deletions

View File

@ -77,12 +77,13 @@ public:
/// GPS status codes
enum GPS_Status {
NO_GPS = 0, ///< No GPS connected/detected
NO_FIX = 1, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK = 5, ///< Receiving valid messages and 3D lock, with relative-positioning improvements
NO_GPS = GPS_FIX_TYPE_NO_GPS, ///< No GPS connected/detected
NO_FIX = GPS_FIX_TYPE_NO_FIX, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT, ///< Receiving valid messages and 3D RTK Float
GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED, ///< Receiving valid messages and 3D RTK Fixed
};
// GPS navigation engine settings. Not all GPS receivers support

View File

@ -170,9 +170,9 @@ AP_GPS_ERB::_parse_gps(void)
_buffer.stat.fix_type);
if (_buffer.stat.fix_status & STAT_FIX_VALID) {
if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_FIX) {
next_fix = AP_GPS::GPS_OK_FIX_3D_RTK;
next_fix = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
} else if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_FLOAT) {
next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
next_fix = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
} else if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_SINGLE) {
next_fix = AP_GPS::GPS_OK_FIX_3D;
} else {

View File

@ -32,7 +32,7 @@ public:
// Methods
bool read();
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK; }
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
static bool _detect(struct ERB_detect_state &state, uint8_t data);

View File

@ -283,7 +283,7 @@ AP_GPS_GSOF::process_message(void)
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
if ((posf2 & 4) == 4)
{
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
}
}
}

View File

@ -28,7 +28,7 @@ public:
AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
AP_GPS::GPS_Status highest_supported_status(void) {
return AP_GPS::GPS_OK_FIX_3D_RTK;
return AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
}
// Methods

View File

@ -224,9 +224,11 @@ AP_GPS_NOVA::process_message(void)
case 32: // l1 float
case 33: // iono float
case 34: // narrow float
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
break;
case 48: // l1 int
case 50: // narrow int
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
break;
case 0: // NONE
case 1: // FIXEDPOS

View File

@ -27,7 +27,7 @@ class AP_GPS_NOVA : public AP_GPS_Backend
public:
AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK; }
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
// Methods
bool read();

View File

@ -260,19 +260,19 @@ AP_GPS_SBF::process_message(void)
state.status = AP_GPS::GPS_OK_FIX_3D;
break;
case 4: // rtk fixed
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
break;
case 5: // rtk float
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
break;
case 6: // sbas
state.status = AP_GPS::GPS_OK_FIX_3D;
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
break;
case 7: // moving rtk fixed
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
break;
case 8: // moving rtk float
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
break;
}

View File

@ -29,7 +29,7 @@ class AP_GPS_SBF : public AP_GPS_Backend
public:
AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK; }
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
// Methods
bool read();

View File

@ -285,7 +285,7 @@ AP_GPS_SBP::_attempt_state_update()
else if (pos_llh->flags == 2)
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
else if (pos_llh->flags == 1)
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
last_full_update_tow = last_vel_ned.tow;

View File

@ -29,7 +29,7 @@ class AP_GPS_SBP : public AP_GPS_Backend
public:
AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK; }
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT; }
// Methods
bool read();

View File

@ -358,7 +358,7 @@ AP_GPS_UBLOX::read(void)
_delay_time = 750;
}
} else {
_delay_time = 4000;
_delay_time = 2000;
}
}
@ -970,11 +970,13 @@ AP_GPS_UBLOX::_parse_gps(void)
if (_buffer.pvt.flags & 0b00000010) // diffsoln
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
if (_buffer.pvt.flags & 0b01000000) // carrsoln - float
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed
state.status = AP_GPS::GPS_OK_FIX_3D_RTK;
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
break;
case 4:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO,
"Unexpected state %d", _buffer.pvt.flags);
state.status = AP_GPS::GPS_OK_FIX_3D;
break;
case 5:
@ -1010,10 +1012,6 @@ AP_GPS_UBLOX::_parse_gps(void)
}
state.last_gps_time_ms = AP_HAL::millis();
if (state.time_week_ms + 220 > _buffer.pvt.itow) {
// we got a 5Hz update.
_last_5hz_time = state.last_gps_time_ms;
}
// time
state.time_week_ms = _buffer.pvt.itow;
@ -1287,7 +1285,8 @@ static const char *reasons[] = {"navigation rate",
"version",
"navigation settings",
"GNSS settings",
"SBAS settings"};
"SBAS settings",
"PVT rate"};
void

View File

@ -37,7 +37,7 @@
* modules are configured with all ubx binary messages off, which
* would mean we would never detect it.
*/
#define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0003,0001,115200,0*1E\r\n"
#define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n"
#define UBLOX_RXM_RAW_LOGGING 1
#define UBLOX_MAX_RXM_RAW_SATS 22
@ -96,7 +96,7 @@ public:
// Methods
bool read();
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK; }
AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
static bool _detect(struct UBLOX_detect_state &state, uint8_t data);