From 0cf4254290cb49728e8fb717ba6382a934bbff81 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Jan 2022 22:23:44 +1100 Subject: [PATCH] ArduPlane: move RPM sensor logging into AP_RPM --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/Plane.h | 1 - ArduPlane/sensors.cpp | 11 ----------- 3 files changed, 1 insertion(+), 13 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index b1113de0f7..0dd3ba594e 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -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 diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 27ce3cdd55..1618fbb5c4 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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; diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index 5a7913ef0e..b2e5b9817a 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -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); - } -}