mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_GPS: Fix a typo on spelling received
This commit is contained in:
parent
c8c34f54cc
commit
c29b19f768
@ -49,7 +49,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART
|
||||
_payload_counter(0),
|
||||
_fix_count(0),
|
||||
_class(0),
|
||||
noRecievedHdop(true),
|
||||
noReceivedHdop(true),
|
||||
_new_position(0),
|
||||
_new_speed(0),
|
||||
need_rate_update(false),
|
||||
@ -580,7 +580,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
break;
|
||||
case MSG_DOP:
|
||||
Debug("MSG_DOP");
|
||||
noRecievedHdop = false;
|
||||
noReceivedHdop = false;
|
||||
state.hdop = _buffer.dop.hDOP;
|
||||
#if UBLOX_FAKE_3DLOCK
|
||||
state.hdop = 130;
|
||||
@ -606,7 +606,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
next_fix = AP_GPS::NO_FIX;
|
||||
state.status = AP_GPS::NO_FIX;
|
||||
}
|
||||
if(noRecievedHdop) {
|
||||
if(noReceivedHdop) {
|
||||
state.hdop = _buffer.solution.position_DOP;
|
||||
}
|
||||
state.num_sats = _buffer.solution.satellites;
|
||||
|
@ -402,7 +402,7 @@ private:
|
||||
uint8_t rate_update_step;
|
||||
uint32_t _last_5hz_time;
|
||||
|
||||
bool noRecievedHdop;
|
||||
bool noReceivedHdop;
|
||||
|
||||
void _configure_navigation_rate(uint16_t rate_ms);
|
||||
void _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
||||
|
Loading…
Reference in New Issue
Block a user