mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_GPS: added fix type to setHIL
This commit is contained in:
parent
09cce5d24e
commit
d7b2a09919
@ -46,7 +46,8 @@ bool AP_GPS_HIL::read(void)
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS_HIL::setHIL(uint64_t _time_epoch_ms, float _latitude, float _longitude, float _altitude,
|
void AP_GPS_HIL::setHIL(Fix_Status fix_status,
|
||||||
|
uint64_t _time_epoch_ms, float _latitude, float _longitude, float _altitude,
|
||||||
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
||||||
{
|
{
|
||||||
time_week = _time_epoch_ms / (86400*7*(uint64_t)1000);
|
time_week = _time_epoch_ms / (86400*7*(uint64_t)1000);
|
||||||
@ -58,7 +59,7 @@ void AP_GPS_HIL::setHIL(uint64_t _time_epoch_ms, float _latitude, float _longitu
|
|||||||
ground_course_cd = _ground_course*1.0e2f;
|
ground_course_cd = _ground_course*1.0e2f;
|
||||||
speed_3d_cm = _speed_3d*1.0e2f;
|
speed_3d_cm = _speed_3d*1.0e2f;
|
||||||
num_sats = _num_sats;
|
num_sats = _num_sats;
|
||||||
fix = num_sats>5?FIX_3D:FIX_NONE;
|
fix = fix_status,
|
||||||
hdop = 200;
|
hdop = 200;
|
||||||
_updated = true;
|
_updated = true;
|
||||||
}
|
}
|
||||||
|
@ -45,7 +45,8 @@ public:
|
|||||||
* @param speed_3d - ground speed in meters/second
|
* @param speed_3d - ground speed in meters/second
|
||||||
* @param altitude - altitude in meters
|
* @param altitude - altitude in meters
|
||||||
*/
|
*/
|
||||||
virtual void setHIL(uint64_t time_epoch_ms, float latitude, float longitude, float altitude,
|
virtual void setHIL(Fix_Status fix_status,
|
||||||
|
uint64_t time_epoch_ms, float latitude, float longitude, float altitude,
|
||||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -113,7 +113,8 @@ GPS::update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
GPS::setHIL(uint64_t _time_epoch_ms, float _latitude, float _longitude, float _altitude,
|
GPS::setHIL(Fix_Status fix_status,
|
||||||
|
uint64_t _time_epoch_ms, float _latitude, float _longitude, float _altitude,
|
||||||
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
@ -105,7 +105,8 @@ public:
|
|||||||
bool print_errors; ///< deprecated
|
bool print_errors; ///< deprecated
|
||||||
|
|
||||||
// HIL support
|
// HIL support
|
||||||
virtual void setHIL(uint64_t time_epoch_ms, float latitude, float longitude, float altitude,
|
virtual void setHIL(Fix_Status fix_status,
|
||||||
|
uint64_t time_epoch_ms, float latitude, float longitude, float altitude,
|
||||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||||
|
|
||||||
// components of velocity in 2D, in m/s
|
// components of velocity in 2D, in m/s
|
||||||
|
Loading…
Reference in New Issue
Block a user