GPS-HIL: set new_data on setHIL()

this fixes navigation for ACM in HIL

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2909 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-18 12:42:36 +00:00
parent a0d599ad95
commit f915eb7052
1 changed files with 1 additions and 0 deletions

View File

@ -45,6 +45,7 @@ void AP_GPS_HIL::setHIL(long _time, float _latitude, float _longitude, float _al
speed_3d = _speed_3d*1.0e2;
num_sats = _num_sats;
fix = true;
new_data = true;
_updated = true;
}