ArduCopter: 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 99a3d253db
commit b4ff6ddfb7
3 changed files with 1 additions and 16 deletions

View File

@ -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),

View File

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

View File

@ -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
}