From 4785515253bf11828947c197e8cfee37c08424d5 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Mon, 3 Feb 2025 18:16:46 +0530 Subject: [PATCH] AP_RPM: use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED --- libraries/AP_RPM/AP_RPM.cpp | 2 +- libraries/AP_RPM/AP_RPM.h | 3 ++- libraries/AP_RPM/AP_RPM_Params.cpp | 2 +- libraries/AP_RPM/AP_RPM_Params.h | 2 +- 4 files changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 30bfcedc60ef57..3e02895fc8934b 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -325,7 +325,7 @@ void AP_RPM::Log_RPM() const } #endif -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED // Return the sensor id to use for streaming over DroneCAN, negative number disables int8_t AP_RPM::get_dronecan_sensor_id(uint8_t instance) const { diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index e2643527cf1610..99849b5d4e121c 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -22,6 +22,7 @@ #include #include #include +#include #include "AP_RPM_Params.h" class AP_RPM_Backend; @@ -107,7 +108,7 @@ class AP_RPM // check settings are valid bool arming_checks(size_t buflen, char *buffer) const; -#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +#if AP_PERIPH_RPM_STREAM_ENABLED // Return the sensor id to use for streaming over DroneCAN, negative number disables int8_t get_dronecan_sensor_id(uint8_t instance) const; #endif diff --git a/libraries/AP_RPM/AP_RPM_Params.cpp b/libraries/AP_RPM/AP_RPM_Params.cpp index dc6f9bb116e410..95c18b6246ef6b 100644 --- a/libraries/AP_RPM/AP_RPM_Params.cpp +++ b/libraries/AP_RPM/AP_RPM_Params.cpp @@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0), #endif -#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) +#if AP_RPM_DRONECAN_ENABLED || AP_PERIPH_RPM_STREAM_ENABLED // @Param: DC_ID // @DisplayName: DroneCAN Sensor ID // @Description: DroneCAN sensor ID to assign to this backend diff --git a/libraries/AP_RPM/AP_RPM_Params.h b/libraries/AP_RPM/AP_RPM_Params.h index 5d2f6a7cf925a9..61c231fed1c5f4 100644 --- a/libraries/AP_RPM/AP_RPM_Params.h +++ b/libraries/AP_RPM/AP_RPM_Params.h @@ -33,7 +33,7 @@ class AP_RPM_Params { #if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED AP_Int8 esc_telem_outbound_index; #endif -#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) +#if AP_RPM_DRONECAN_ENABLED || AP_PERIPH_RPM_STREAM_ENABLED AP_Int8 dronecan_sensor_id; #endif static const struct AP_Param::GroupInfo var_info[];