Skip to content

Commit

Permalink
AP_RPM: create and use AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM…
Browse files Browse the repository at this point in the history
…_ENABLED defines for HAL_PERIPH_ENABLE_RPM and HAL_PERIPH_ENABLE_RPM_STREAM
  • Loading branch information
shiv-tyagi committed Feb 3, 2025
1 parent 89f189c commit a11d03e
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RPM/AP_RPM_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -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[];
Expand Down

0 comments on commit a11d03e

Please sign in to comment.