mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
SITL: fixed drift rate limit in simulator
This commit is contained in:
parent
53ebcfeba5
commit
99d21854f9
@ -41,7 +41,8 @@ uint32_t AP_InertialSensor_Stub::get_last_sample_time_micros() {
|
|||||||
return _last_update_ms * 1000;
|
return _last_update_ms * 1000;
|
||||||
}
|
}
|
||||||
float AP_InertialSensor_Stub::get_gyro_drift_rate(void) {
|
float AP_InertialSensor_Stub::get_gyro_drift_rate(void) {
|
||||||
return 0.0;
|
// 0.5 degrees/second/minute
|
||||||
|
return ToRad(0.5/60);
|
||||||
}
|
}
|
||||||
uint16_t AP_InertialSensor_Stub::num_samples_available()
|
uint16_t AP_InertialSensor_Stub::num_samples_available()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user