mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: added setHil_Accuracy()
This commit is contained in:
parent
772acf056b
commit
4e5f1374da
@ -492,6 +492,19 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
|
||||
_type[instance].set(GPS_TYPE_HIL);
|
||||
}
|
||||
|
||||
// set accuracy for HIL
|
||||
void AP_GPS::setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc)
|
||||
{
|
||||
GPS_State &istate = state[instance];
|
||||
istate.vdop = vdop;
|
||||
istate.horizontal_accuracy = hacc;
|
||||
istate.vertical_accuracy = vacc;
|
||||
istate.speed_accuracy = sacc;
|
||||
istate.have_horizontal_accuracy = true;
|
||||
istate.have_vertical_accuracy = true;
|
||||
istate.have_speed_accuracy = true;
|
||||
}
|
||||
|
||||
/**
|
||||
Lock a GPS port, prevening the GPS driver from using it. This can
|
||||
be used to allow a user to control a GPS port via the
|
||||
|
@ -307,6 +307,9 @@ public:
|
||||
const Location &location, const Vector3f &velocity, uint8_t num_sats,
|
||||
uint16_t hdop, bool _have_vertical_velocity);
|
||||
|
||||
// set accuracy for HIL
|
||||
void setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// dataflash for logging, if available
|
||||
|
Loading…
Reference in New Issue
Block a user