AP_RPM: use RPM_SCALING in SITL

useful for testing low RPM warning in a GCS
This commit is contained in:
Andrew Tridgell 2016-09-01 17:43:28 +10:00
parent acbeb29fbe
commit 232347569f
1 changed files with 1 additions and 0 deletions

View File

@ -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();
}