mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: use RPM_SCALING in SITL
useful for testing low RPM warning in a GCS
This commit is contained in:
parent
acbeb29fbe
commit
232347569f
|
@ -41,6 +41,7 @@ void AP_RPM_SITL::update(void)
|
|||
} else {
|
||||
state.rate_rpm = sitl->state.rpm2;
|
||||
}
|
||||
state.rate_rpm *= ap_rpm._scaling[state.instance];
|
||||
state.signal_quality = 0.5f;
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue