mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_GPS: added UBLOX_FAKE_3DLOCK debugging option
useful when unable to get 3D lock
This commit is contained in:
parent
f1e120113c
commit
cee8a017ab
@ -23,6 +23,7 @@
|
||||
#include <AP_HAL.h>
|
||||
|
||||
#define UBLOX_DEBUGGING 0
|
||||
#define UBLOX_FAKE_3DLOCK 0
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -78,6 +79,8 @@ AP_GPS_UBLOX::send_next_rate_update(void)
|
||||
return;
|
||||
}
|
||||
|
||||
//hal.console->printf_P(PSTR("next_rate: %u\n"), (unsigned)rate_update_step);
|
||||
|
||||
switch (rate_update_step) {
|
||||
case 0:
|
||||
_configure_navigation_rate(200);
|
||||
@ -296,6 +299,10 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
next_fix = GPS::FIX_NONE;
|
||||
fix = GPS::FIX_NONE;
|
||||
}
|
||||
#if UBLOX_FAKE_3DLOCK
|
||||
fix = GPS::FIX_3D;
|
||||
next_fix = fix;
|
||||
#endif
|
||||
break;
|
||||
case MSG_SOL:
|
||||
Debug("MSG_SOL fix_status=%u fix_type=%u",
|
||||
@ -316,6 +323,10 @@ AP_GPS_UBLOX::_parse_gps(void)
|
||||
}
|
||||
num_sats = _buffer.solution.satellites;
|
||||
hdop = _buffer.solution.position_DOP;
|
||||
#if UBLOX_FAKE_3DLOCK
|
||||
next_fix = fix;
|
||||
num_sats = 10;
|
||||
#endif
|
||||
break;
|
||||
case MSG_VELNED:
|
||||
Debug("MSG_VELNED");
|
||||
|
Loading…
Reference in New Issue
Block a user