mirror of https://github.com/ArduPilot/ardupilot
Fixed several HIL class bugs.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@914 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
c473af0082
commit
9331f8616c
|
@ -30,20 +30,24 @@ void AP_GPS_HIL::update(void)
|
|||
|
||||
int AP_GPS_HIL::status(void)
|
||||
{
|
||||
return 2; // gps locked
|
||||
// TODO: show as locked after first packet received
|
||||
if (valid_read)
|
||||
{
|
||||
if (fix) return 2;
|
||||
else return 1;
|
||||
}
|
||||
else return 0;
|
||||
}
|
||||
|
||||
void AP_GPS_HIL::setHIL(long _time, long _latitude, long _longitude, long _altitude,
|
||||
long _ground_speed, long _ground_course, long _speed_3d, uint8_t _num_sats)
|
||||
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*1e7;
|
||||
longitude = _longitude*1e7;
|
||||
altitude = _altitude*1e2;
|
||||
ground_speed = _ground_speed*1e2;
|
||||
ground_course = _ground_course*1e2;
|
||||
speed_3d = _speed_3d*1e2;
|
||||
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;
|
||||
|
|
|
@ -30,8 +30,8 @@ public:
|
|||
* @param speed_3d - ground speed in meters/second
|
||||
* @param altitude - altitude in meters
|
||||
*/
|
||||
void setHIL(long time, long latitude, long longitude, long altitude,
|
||||
long ground_speed, long ground_course, long speed_3d, uint8_t num_sats);
|
||||
void setHIL(long time, float latitude, float longitude, float altitude,
|
||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||
};
|
||||
|
||||
#endif // AP_GPS_HIL_H
|
||||
|
|
Loading…
Reference in New Issue