|
|
|
@ -41,17 +41,17 @@ int AP_GPS_HIL::status(void)
@@ -41,17 +41,17 @@ int AP_GPS_HIL::status(void)
|
|
|
|
|
void AP_GPS_HIL::setHIL(long _time, float _latitude, float _longitude, float _altitude, |
|
|
|
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats) |
|
|
|
|
{ |
|
|
|
|
time = _time; |
|
|
|
|
latitude = _latitude*1.0e7; |
|
|
|
|
longitude = _longitude*1.0e7; |
|
|
|
|
altitude = _altitude*1.0e2; |
|
|
|
|
ground_speed = _ground_speed*1.0e2; |
|
|
|
|
ground_course = _ground_course*1.0e2; |
|
|
|
|
speed_3d = _speed_3d*1.0e2; |
|
|
|
|
num_sats = _num_sats; |
|
|
|
|
new_data = true; |
|
|
|
|
fix = true; |
|
|
|
|
valid_read = true; |
|
|
|
|
time = _time; |
|
|
|
|
latitude = _latitude*1.0e7; |
|
|
|
|
longitude = _longitude*1.0e7; |
|
|
|
|
altitude = _altitude*1.0e2; |
|
|
|
|
ground_speed = _ground_speed*1.0e2; |
|
|
|
|
ground_course = _ground_course*1.0e2; |
|
|
|
|
speed_3d = _speed_3d*1.0e2; |
|
|
|
|
num_sats = _num_sats; |
|
|
|
|
new_data = true; |
|
|
|
|
fix = true; |
|
|
|
|
valid_read = true; |
|
|
|
|
_setTime(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|