AC remove attitude hil unused extra (gps jump issue.)

This commit is contained in:
Michael Oborne 2012-07-29 08:18:41 +08:00
parent 38ff381620
commit 2d6d74f625
1 changed files with 0 additions and 3 deletions

View File

@ -869,9 +869,6 @@ GCS_MAVLINK::data_stream_send(void)
if (stream_trigger(STREAM_POSITION)) {
// sent with GPS read
#if HIL_MODE == HIL_MODE_ATTITUDE
send_message(MSG_LOCATION);
#endif
//Serial.printf("mav3 %d\n", (int)streamRatePosition.get());
}