ArduPlane: move RPM sensor logging into AP_RPM

This commit is contained in:
Peter Barker 2022-01-05 22:23:44 +11:00 committed by Andrew Tridgell
parent b4ff6ddfb7
commit 0cf4254290
3 changed files with 1 additions and 13 deletions

View File

@ -90,7 +90,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(one_second_loop, 1, 400, 90),
SCHED_TASK(three_hz_loop, 3, 75, 93),
SCHED_TASK(check_long_failsafe, 3, 400, 96),
SCHED_TASK(rpm_update, 10, 100, 99),
SCHED_TASK_CLASS(AP_RPM, &plane.rpm_sensor, update, 10, 100, 99),
#if AP_AIRSPEED_AUTOCAL_ENABLE
SCHED_TASK(airspeed_ratio_update, 1, 100, 102),
#endif // AP_AIRSPEED_AUTOCAL_ENABLE

View File

@ -1048,7 +1048,6 @@ private:
// sensors.cpp
void read_rangefinder(void);
void read_airspeed(void);
void rpm_update(void);
// system.cpp
void init_ardupilot() override;

View File

@ -58,14 +58,3 @@ void Plane::read_airspeed(void)
const float dt = 0.1;
surface_speed_scaler += calc_lowpass_alpha_dt(dt, cutoff_Hz) * (speed_scaler - surface_speed_scaler);
}
/*
update RPM sensors
*/
void Plane::rpm_update(void)
{
rpm_sensor.update();
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
logger.Write_RPM(rpm_sensor);
}
}