AP_RPM: use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED

This commit is contained in:
Shiv Tyagi 2025-02-03 18:16:46 +05:30 committed by Peter Barker
parent abc605c7e4
commit 8655d013c6
5 changed files with 8 additions and 4 deletions

View File

@ -325,7 +325,7 @@ void AP_RPM::Log_RPM() const
} }
#endif #endif
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM #if AP_RPM_STREAM_ENABLED
// Return the sensor id to use for streaming over DroneCAN, negative number disables // 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 int8_t AP_RPM::get_dronecan_sensor_id(uint8_t instance) const
{ {

View File

@ -107,7 +107,7 @@ public:
// check settings are valid // check settings are valid
bool arming_checks(size_t buflen, char *buffer) const; bool arming_checks(size_t buflen, char *buffer) const;
#ifdef HAL_PERIPH_ENABLE_RPM_STREAM #if AP_RPM_STREAM_ENABLED
// Return the sensor id to use for streaming over DroneCAN, negative number disables // Return the sensor id to use for streaming over DroneCAN, negative number disables
int8_t get_dronecan_sensor_id(uint8_t instance) const; int8_t get_dronecan_sensor_id(uint8_t instance) const;
#endif #endif

View File

@ -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), AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0),
#endif #endif
#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) #if AP_RPM_DRONECAN_ENABLED || AP_RPM_STREAM_ENABLED
// @Param: DC_ID // @Param: DC_ID
// @DisplayName: DroneCAN Sensor ID // @DisplayName: DroneCAN Sensor ID
// @Description: DroneCAN sensor ID to assign to this backend // @Description: DroneCAN sensor ID to assign to this backend

View File

@ -33,7 +33,7 @@ public:
#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED #if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED
AP_Int8 esc_telem_outbound_index; AP_Int8 esc_telem_outbound_index;
#endif #endif
#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) #if AP_RPM_DRONECAN_ENABLED || AP_RPM_STREAM_ENABLED
AP_Int8 dronecan_sensor_id; AP_Int8 dronecan_sensor_id;
#endif #endif
static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info[];

View File

@ -53,3 +53,7 @@
#if AP_RPM_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS #if AP_RPM_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS
#error AP_RPM_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS #error AP_RPM_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS
#endif #endif
#ifndef AP_RPM_STREAM_ENABLED
#define AP_RPM_STREAM_ENABLED 0
#endif