mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
GPS: added FAKE_GPS_LOCK_TIME
this allows you to fake up a GPS lock after a specific number of seconds
This commit is contained in:
parent
346a572440
commit
b4965d34a9
@ -13,6 +13,7 @@
|
|||||||
|
|
||||||
#include "AP_GPS_MTK16.h"
|
#include "AP_GPS_MTK16.h"
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <wiring.h>
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
|
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
|
||||||
@ -141,6 +142,15 @@ restart:
|
|||||||
|
|
||||||
parsed = true;
|
parsed = true;
|
||||||
|
|
||||||
|
#ifdef FAKE_GPS_LOCK_TIME
|
||||||
|
if (millis() > FAKE_GPS_LOCK_TIME*1000) {
|
||||||
|
fix = true;
|
||||||
|
latitude = -35000000UL;
|
||||||
|
longitude = 149000000UL;
|
||||||
|
altitude = 584;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Waiting on clarification of MAVLink protocol!
|
/* Waiting on clarification of MAVLink protocol!
|
||||||
if(!_offset_calculated && parsed) {
|
if(!_offset_calculated && parsed) {
|
||||||
long tempd1 = date;
|
long tempd1 = date;
|
||||||
|
Loading…
Reference in New Issue
Block a user