diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 51c82e6d56..bde0d4bb50 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -76,7 +76,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60), SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63), #if RPM_ENABLED == ENABLED - SCHED_TASK(rpm_update, 10, 200, 66), + SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update 10, 200, 66), #endif SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100, 69), SCHED_TASK(terrain_update, 10, 100, 72), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index f713f9b6ae..7289ebe1fd 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -406,9 +406,6 @@ private: float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt); void update_poscon_alt_max(); void rotate_body_frame_to_NE(float &x, float &y); -#if RPM_ENABLED == ENABLED - void rpm_update(); -#endif void Log_Write_Control_Tuning(); void Log_Write_Attitude(); void Log_Write_MotBatt(); diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index bb1aca8945..278798cca2 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -71,19 +71,6 @@ bool Sub::rangefinder_alt_ok() const return (rangefinder_state.enabled && rangefinder_state.alt_healthy); } -/* - update RPM sensors - */ -#if RPM_ENABLED == ENABLED -void Sub::rpm_update(void) -{ - rpm_sensor.update(); - if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { - logger.Write_RPM(rpm_sensor); - } -} -#endif - /* ask airspeed sensor for a new value, duplicated from plane */