HIL: send location information

we don't send MSG_LOCATION in HIL mode during GPS updates, as we don't
call the GPS update routines, so we need to send MSG_LOCATION as part
of the Position stream

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2892 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-17 10:33:33 +00:00
parent aff9e9a831
commit 93a8deac7d

View File

@ -99,7 +99,9 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
if (freqLoopMatch(streamRatePosition, freqMin, freqMax)) {
// sent with GPS read
//send_message(MSG_LOCATION);
#if HIL_MODE == HIL_MODE_ATTITUDE
send_message(MSG_LOCATION);
#endif
//Serial.printf("mav3 %d\n", (int)streamRatePosition.get());
}