diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index d7bb3c69d7caf4..a52eb0c374ddea 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -296,7 +296,7 @@ void AP_Periph_FW::init() nmea.init(); #endif -#ifdef HAL_PERIPH_ENABLE_RPM +#if AP_PERIPH_RPM_ENABLED rpm_sensor.init(); #endif @@ -522,7 +522,7 @@ void AP_Periph_FW::update() temperature_sensor.update(); #endif -#ifdef HAL_PERIPH_ENABLE_RPM +#if AP_PERIPH_RPM_ENABLED if (now - rpm_last_update_ms >= 100) { rpm_last_update_ms = now; rpm_sensor.update(); diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 10bc771119c681..6a0f310ccfc8e1 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -92,8 +92,8 @@ #endif #endif -#if defined(HAL_PERIPH_ENABLE_RPM_STREAM) && !defined(HAL_PERIPH_ENABLE_RPM) - #error "HAL_PERIPH_ENABLE_RPM_STREAM requires HAL_PERIPH_ENABLE_RPM" +#if AP_PERIPH_RPM_STREAM_ENABLED && !AP_PERIPH_RPM_ENABLED + #error "AP_PERIPH_RPM_STREAM_ENABLED requires AP_PERIPH_RPM_ENABLED" #endif #ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED @@ -239,15 +239,15 @@ class AP_Periph_FW { AP_InertialSensor imu; #endif -#ifdef HAL_PERIPH_ENABLE_RPM +#if AP_PERIPH_RPM_ENABLED AP_RPM rpm_sensor; uint32_t rpm_last_update_ms; -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED void rpm_sensor_send(); uint32_t rpm_last_send_ms; uint8_t rpm_last_sent_index; #endif -#endif // HAL_PERIPH_ENABLE_RPM +#endif // AP_PERIPH_RPM_ENABLED #if AP_PERIPH_BATTERY_ENABLED void handle_battery_failsafe(const char* type_str, const int8_t action) { } diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index ace23b6df84292..6151015f766c00 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -625,7 +625,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(networking_periph, "NET_", Networking_Periph), #endif -#ifdef HAL_PERIPH_ENABLE_RPM +#if AP_PERIPH_RPM_ENABLED // @Group: RPM // @Path: ../libraries/AP_RPM/AP_RPM.cpp GOBJECT(rpm_sensor, "RPM", AP_RPM), @@ -701,7 +701,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @User: Standard GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS), -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED // @Param: RPM_MSG_RATE // @DisplayName: RPM sensor message rate // @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn. diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index fff21ce8ffb9e1..64ab02de8a51ba 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -225,7 +225,7 @@ class Parameters { AP_Int8 temperature_msg_rate; #endif -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED AP_Int16 rpm_msg_rate; #endif diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index d8cb8e28101bfe..9b8706b8fa00fe 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1966,7 +1966,7 @@ void AP_Periph_FW::can_update() #ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE temperature_sensor_update(); #endif -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED rpm_sensor_send(); #endif } diff --git a/Tools/AP_Periph/rpm.cpp b/Tools/AP_Periph/rpm.cpp index b017fb04157e3e..81cf2dcc0cfeab 100644 --- a/Tools/AP_Periph/rpm.cpp +++ b/Tools/AP_Periph/rpm.cpp @@ -1,6 +1,6 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED #include @@ -52,4 +52,4 @@ void AP_Periph_FW::rpm_sensor_send(void) } } -#endif // HAL_PERIPH_ENABLE_RPM_STREAM +#endif // AP_PERIPH_RPM_STREAM_ENABLED diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 4fc25ee3413388..66b8920565c734 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -961,8 +961,8 @@ def configure_env(self, cfg, env): AP_PERIPH_BATTERY_ENABLED = 1, AP_PERIPH_BATTERY_BALANCE_ENABLED = 0, HAL_PERIPH_ENABLE_EFI = 1, - HAL_PERIPH_ENABLE_RPM = 1, - HAL_PERIPH_ENABLE_RPM_STREAM = 1, + AP_PERIPH_RPM_ENABLED = 1, + AP_PERIPH_RPM_STREAM_ENABLED = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1,