AP_GPS: Read actual hDOP value from UBLOX messages

Before we were reading the position DOP and calling it hDOP. Since the
other drivers actualy read hDOP it seem best to do the same.
Fixes issue 462.
This commit is contained in:
Andy Piper 2015-07-14 14:09:43 +09:00 committed by Randy Mackay
parent 4e3d0ae0c1
commit 5ccc58ffb4
2 changed files with 27 additions and 7 deletions

View File

@ -109,26 +109,29 @@ AP_GPS_UBLOX::send_next_rate_update(void)
case 4: case 4:
_configure_message_rate(CLASS_NAV, MSG_VELNED, 1); // 36+8 bytes _configure_message_rate(CLASS_NAV, MSG_VELNED, 1); // 36+8 bytes
break; break;
#if UBLOX_HW_LOGGING
case 5: case 5:
_configure_message_rate(CLASS_NAV, MSG_DOP, 1); // 18+8 bytes
break;
#if UBLOX_HW_LOGGING
case 6:
// gather MON_HW at 0.5Hz // gather MON_HW at 0.5Hz
_configure_message_rate(CLASS_MON, MSG_MON_HW, 2); // 64+8 bytes _configure_message_rate(CLASS_MON, MSG_MON_HW, 2); // 64+8 bytes
break; break;
case 6: case 7:
// gather MON_HW2 at 0.5Hz // gather MON_HW2 at 0.5Hz
_configure_message_rate(CLASS_MON, MSG_MON_HW2, 2); // 24+8 bytes _configure_message_rate(CLASS_MON, MSG_MON_HW2, 2); // 24+8 bytes
break; break;
#endif #endif
#if UBLOX_RXM_RAW_LOGGING #if UBLOX_RXM_RAW_LOGGING
case 7: case 8:
_configure_message_rate(CLASS_RXM, MSG_RXM_RAW, gps._raw_data); _configure_message_rate(CLASS_RXM, MSG_RXM_RAW, gps._raw_data);
break; break;
case 8: case 9:
_configure_message_rate(CLASS_RXM, MSG_RXM_RAWX, gps._raw_data); _configure_message_rate(CLASS_RXM, MSG_RXM_RAWX, gps._raw_data);
break; break;
#endif #endif
#if UBLOX_VERSION_AUTODETECTION #if UBLOX_VERSION_AUTODETECTION
case 9: case 10:
_request_version(); _request_version();
break; break;
#endif #endif
@ -531,6 +534,13 @@ AP_GPS_UBLOX::_parse_gps(void)
#if UBLOX_FAKE_3DLOCK #if UBLOX_FAKE_3DLOCK
state.status = AP_GPS::GPS_OK_FIX_3D; state.status = AP_GPS::GPS_OK_FIX_3D;
next_fix = state.status; next_fix = state.status;
#endif
break;
case MSG_DOP:
Debug("MSG_DOP");
state.hdop = _buffer.dop.hDOP;
#if UBLOX_FAKE_3DLOCK
state.hdop = 200;
#endif #endif
break; break;
case MSG_SOL: case MSG_SOL:
@ -554,7 +564,6 @@ AP_GPS_UBLOX::_parse_gps(void)
state.status = AP_GPS::NO_FIX; state.status = AP_GPS::NO_FIX;
} }
state.num_sats = _buffer.solution.satellites; state.num_sats = _buffer.solution.satellites;
state.hdop = _buffer.solution.position_DOP;
if (next_fix >= AP_GPS::GPS_OK_FIX_2D) { if (next_fix >= AP_GPS::GPS_OK_FIX_2D) {
state.last_gps_time_ms = hal.scheduler->millis(); state.last_gps_time_ms = hal.scheduler->millis();
if (state.time_week == _buffer.solution.week && if (state.time_week == _buffer.solution.week &&
@ -570,7 +579,6 @@ AP_GPS_UBLOX::_parse_gps(void)
#if UBLOX_FAKE_3DLOCK #if UBLOX_FAKE_3DLOCK
next_fix = state.status; next_fix = state.status;
state.num_sats = 10; state.num_sats = 10;
state.hdop = 200;
state.time_week = 1721; state.time_week = 1721;
state.time_week_ms = hal.scheduler->millis() + 3*60*60*1000 + 37000; state.time_week_ms = hal.scheduler->millis() + 3*60*60*1000 + 37000;
state.last_gps_time_ms = hal.scheduler->millis(); state.last_gps_time_ms = hal.scheduler->millis();

View File

@ -121,6 +121,16 @@ private:
uint32_t time_to_first_fix; uint32_t time_to_first_fix;
uint32_t uptime; // milliseconds uint32_t uptime; // milliseconds
}; };
struct PACKED ubx_nav_dop {
uint32_t time; // GPS msToW
uint16_t gDOP;
uint16_t pDOP;
uint16_t tDOP;
uint16_t vDOP;
uint16_t hDOP;
uint16_t nDOP;
uint16_t eDOP;
};
struct PACKED ubx_nav_solution { struct PACKED ubx_nav_solution {
uint32_t time; uint32_t time;
int32_t time_nsec; int32_t time_nsec;
@ -252,6 +262,7 @@ private:
union PACKED { union PACKED {
ubx_nav_posllh posllh; ubx_nav_posllh posllh;
ubx_nav_status status; ubx_nav_status status;
ubx_nav_dop dop;
ubx_nav_solution solution; ubx_nav_solution solution;
ubx_nav_velned velned; ubx_nav_velned velned;
ubx_cfg_nav_settings nav_settings; ubx_cfg_nav_settings nav_settings;
@ -279,6 +290,7 @@ private:
MSG_ACK_ACK = 0x01, MSG_ACK_ACK = 0x01,
MSG_POSLLH = 0x2, MSG_POSLLH = 0x2,
MSG_STATUS = 0x3, MSG_STATUS = 0x3,
MSG_DOP = 0x4,
MSG_SOL = 0x6, MSG_SOL = 0x6,
MSG_VELNED = 0x12, MSG_VELNED = 0x12,
MSG_CFG_PRT = 0x00, MSG_CFG_PRT = 0x00,