mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GPS: fixes after review
Ensure 3D fix before returning velocity_down UBLOX: restore check of fix_status as part of determining 2D or 3D fix SIRF: add missing brackets on fix type check
This commit is contained in:
parent
c2055557f5
commit
27309a553f
@ -174,7 +174,7 @@ AP_GPS_SIRF::_parse_gps(void)
|
|||||||
// parse fix type
|
// parse fix type
|
||||||
if (_buffer.nav.fix_invalid) {
|
if (_buffer.nav.fix_invalid) {
|
||||||
fix = GPS::FIX_NONE;
|
fix = GPS::FIX_NONE;
|
||||||
}else if (_buffer.nav.fix_type & FIX_MASK == FIX_3D) {
|
}else if ((_buffer.nav.fix_type & FIX_MASK) == FIX_3D) {
|
||||||
fix = GPS::FIX_3D;
|
fix = GPS::FIX_3D;
|
||||||
}else{
|
}else{
|
||||||
fix = GPS::FIX_2D;
|
fix = GPS::FIX_2D;
|
||||||
|
@ -228,10 +228,15 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||||||
Debug("MSG_STATUS fix_status=%u fix_type=%u",
|
Debug("MSG_STATUS fix_status=%u fix_type=%u",
|
||||||
_buffer.status.fix_status,
|
_buffer.status.fix_status,
|
||||||
_buffer.status.fix_type);
|
_buffer.status.fix_type);
|
||||||
if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) {
|
||||||
next_fix = GPS::FIX_3D;
|
if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
||||||
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
next_fix = GPS::FIX_3D;
|
||||||
next_fix = GPS::FIX_2D;
|
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
||||||
|
next_fix = GPS::FIX_2D;
|
||||||
|
}else{
|
||||||
|
next_fix = GPS::FIX_NONE;
|
||||||
|
fix = GPS::FIX_NONE;
|
||||||
|
}
|
||||||
}else{
|
}else{
|
||||||
next_fix = GPS::FIX_NONE;
|
next_fix = GPS::FIX_NONE;
|
||||||
fix = GPS::FIX_NONE;
|
fix = GPS::FIX_NONE;
|
||||||
@ -241,10 +246,15 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||||||
Debug("MSG_SOL fix_status=%u fix_type=%u",
|
Debug("MSG_SOL fix_status=%u fix_type=%u",
|
||||||
_buffer.solution.fix_status,
|
_buffer.solution.fix_status,
|
||||||
_buffer.solution.fix_type);
|
_buffer.solution.fix_type);
|
||||||
if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) {
|
||||||
next_fix = GPS::FIX_3D;
|
if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
|
||||||
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
next_fix = GPS::FIX_3D;
|
||||||
next_fix = GPS::FIX_2D;
|
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
|
||||||
|
next_fix = GPS::FIX_2D;
|
||||||
|
}else{
|
||||||
|
next_fix = GPS::FIX_NONE;
|
||||||
|
fix = GPS::FIX_NONE;
|
||||||
|
}
|
||||||
}else{
|
}else{
|
||||||
next_fix = GPS::FIX_NONE;
|
next_fix = GPS::FIX_NONE;
|
||||||
fix = GPS::FIX_NONE;
|
fix = GPS::FIX_NONE;
|
||||||
|
@ -141,7 +141,7 @@ public:
|
|||||||
return _status >= GPS_OK_FIX_2D ? _velocity_east : 0;
|
return _status >= GPS_OK_FIX_2D ? _velocity_east : 0;
|
||||||
}
|
}
|
||||||
float velocity_down(void) {
|
float velocity_down(void) {
|
||||||
return _status >= GPS_OK_FIX_2D ? _velocity_down : 0;
|
return _status >= GPS_OK_FIX_3D ? _velocity_down : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// last ground speed in m/s. This can be used when we have no GPS
|
// last ground speed in m/s. This can be used when we have no GPS
|
||||||
|
Loading…
Reference in New Issue
Block a user