From b4ff6ddfb75b1224af281a2dce307f21e5179a16 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Jan 2022 22:23:44 +1100 Subject: [PATCH] ArduCopter: move RPM sensor logging into AP_RPM --- ArduCopter/Copter.cpp | 2 +- ArduCopter/Copter.h | 1 - ArduCopter/sensors.cpp | 14 -------------- 3 files changed, 1 insertion(+), 16 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 5d50b5b04b..b9de7d75b7 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -184,7 +184,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126), #if RPM_ENABLED == ENABLED - SCHED_TASK(rpm_update, 40, 200, 129), + SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129), #endif SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100, 132), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 4214f8f692..df355f6e96 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -862,7 +862,6 @@ private: void read_rangefinder(void); bool rangefinder_alt_ok() const; bool rangefinder_up_ok() const; - void rpm_update(); void update_optical_flow(void); void compass_cal_update(void); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index b37103b0f9..54968f092f 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -145,17 +145,3 @@ bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) ret += inertial_alt_cm - rangefinder_state.inertial_alt_cm; return true; } - - -/* - update RPM sensors - */ -void Copter::rpm_update(void) -{ -#if RPM_ENABLED == ENABLED - rpm_sensor.update(); - if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { - logger.Write_RPM(rpm_sensor); - } -#endif -}