Skip to content

Commit

Permalink
Tools: replace AP_PERIPH_RPM_ENABLED and AP_PERIPH_RPM_STREAM_ENABLED
Browse files Browse the repository at this point in the history
with HAL_PERIPH_ENABLE_RPM and HAL_PERIPH_ENABLE_RPM_STREAM respectively
  • Loading branch information
shiv-tyagi committed Feb 3, 2025
1 parent 495059e commit ae594cb
Show file tree
Hide file tree
Showing 7 changed files with 15 additions and 15 deletions.
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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();
Expand Down
10 changes: 5 additions & 5 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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) { }
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/rpm.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_RPM_STREAM
#if AP_PERIPH_RPM_STREAM_ENABLED

#include <dronecan_msgs.h>

Expand Down Expand Up @@ -52,4 +52,4 @@ void AP_Periph_FW::rpm_sensor_send(void)
}
}

#endif // HAL_PERIPH_ENABLE_RPM_STREAM
#endif // AP_PERIPH_RPM_STREAM_ENABLED
4 changes: 2 additions & 2 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down

0 comments on commit ae594cb

Please sign in to comment.