mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
4c61462dfd
|
@ -1799,5 +1799,7 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
|||
vsnprintf((char *)pending_status.text, sizeof(pending_status.text), fmtstr, ap);
|
||||
va_end(ap);
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
|
||||
if (gcs3.initialised) {
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -2103,5 +2103,7 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
|
|||
vsnprintf((char *)pending_status.text, sizeof(pending_status.text), fmtstr, ap);
|
||||
va_end(ap);
|
||||
mavlink_send_message(MAVLINK_COMM_0, MSG_STATUSTEXT, 0);
|
||||
if (gcs3.initialised) {
|
||||
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -13,6 +13,7 @@
|
|||
|
||||
#include "AP_GPS_MTK16.h"
|
||||
#include <stdint.h>
|
||||
#include <wiring.h>
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)
|
||||
|
@ -141,6 +142,15 @@ restart:
|
|||
|
||||
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!
|
||||
if(!_offset_calculated && parsed) {
|
||||
long tempd1 = date;
|
||||
|
|
Loading…
Reference in New Issue