diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 3f0134ad0e..e1c7b20af6 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -95,7 +95,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57), 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 +#if AP_RPM_ENABLED SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66), #endif SCHED_TASK(terrain_update, 10, 100, 72), diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index d25c27f475..d526503b2f 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -387,7 +387,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, MSG_VIBRATION, -#if RPM_ENABLED == ENABLED +#if AP_RPM_ENABLED MSG_RPM, #endif MSG_ESC_TELEMETRY, diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 27cf80d582..a9025addf5 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -599,7 +599,7 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif -#if RPM_ENABLED == ENABLED +#if AP_RPM_ENABLED // @Group: RPM // @Path: ../libraries/AP_RPM/AP_RPM.cpp GOBJECT(rpm_sensor, "RPM", AP_RPM), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index e3d0240457..2bb1c402c5 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -81,7 +81,9 @@ #include // RC input mapping library #endif -#if RPM_ENABLED == ENABLED +#include + +#if AP_RPM_ENABLED #include #endif @@ -151,7 +153,7 @@ private: LowPassFilterFloat alt_cm_filt; // altitude filter } rangefinder_state = { false, false, 0, 0 }; -#if RPM_ENABLED == ENABLED +#if AP_RPM_ENABLED AP_RPM rpm_sensor; #endif diff --git a/ArduSub/config.h b/ArduSub/config.h index a7bb740cce..322bd5b9aa 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -34,14 +34,6 @@ # define CIRCLE_NAV_ENABLED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// RPM -// - -#ifndef RPM_ENABLED -# define RPM_ENABLED DISABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // RCMAP // diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index e3d398f053..6fa584378e 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -137,7 +137,7 @@ void Sub::init_ardupilot() #endif // initialise AP_RPM library -#if RPM_ENABLED == ENABLED +#if AP_RPM_ENABLED rpm_sensor.init(); #endif