Skip to content

Commit

Permalink
Tools: create and use AP_PERIPH_RANGEFINDER_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
shiv-tyagi committed Jan 31, 2025
1 parent 48b7827 commit 1306136
Show file tree
Hide file tree
Showing 8 changed files with 12 additions and 12 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 @@ -235,7 +235,7 @@ void AP_Periph_FW::init()

#endif

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
bool have_rangefinder = false;
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
if ((rangefinder.get_type(i) != RangeFinder::Type::NONE) && (g.rangefinder_port[i] >= 0)) {
Expand Down Expand Up @@ -432,7 +432,7 @@ void AP_Periph_FW::update()
#if AP_PERIPH_BARO_ENABLED
hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors());
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
AP_RangeFinder_Backend *backend = rangefinder.get_backend(i);
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ class AP_Periph_FW {
void can_imu_update();
#endif

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
void can_rangefinder_update();
#endif
void can_battery_update();
Expand Down Expand Up @@ -298,7 +298,7 @@ class AP_Periph_FW {
AP_Airspeed airspeed;
#endif

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
RangeFinder rangefinder;
uint32_t last_rangefinder_update_ms;
uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES];
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(airspeed, "ARSPD", AP_Airspeed),
#endif

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
// @Param: RNGFND_BAUDRATE
// @DisplayName: Rangefinder serial baudrate
// @Description: Rangefinder serial baudrate.
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 @@ -126,7 +126,7 @@ class Parameters {
AP_Int8 flash_bootloader;
#endif

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
AP_Int32 rangefinder_baud[RANGEFINDER_MAX_INSTANCES];
AP_Int8 rangefinder_port[RANGEFINDER_MAX_INSTANCES];
AP_Int16 rangefinder_max_rate;
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -361,7 +361,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
AP_Param::setup_object_defaults(&rangefinder, rangefinder.var_info);
#endif
}
Expand Down Expand Up @@ -1900,7 +1900,7 @@ void AP_Periph_FW::can_update()
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
can_airspeed_update();
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
can_rangefinder_update();
#endif
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/rangefinder.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED

/*
rangefinder support
Expand Down Expand Up @@ -118,4 +118,4 @@ void AP_Periph_FW::can_rangefinder_update(void)
}
}

#endif // HAL_PERIPH_ENABLE_RANGEFINDER
#endif // AP_PERIPH_RANGEFINDER_ENABLED
2 changes: 1 addition & 1 deletion Tools/AP_Periph/serial_tunnel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const
uart_num = g.gps_port;
}
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
#if AP_PERIPH_RANGEFINDER_ENABLED
if (uart_num == -1) {
uart_num = g.rangefinder_port[0];
}
Expand Down
2 changes: 1 addition & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -957,7 +957,7 @@ def configure_env(self, cfg, env):
AP_PERIPH_MAG_ENABLED = 1,
AP_PERIPH_BARO_ENABLED = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
AP_PERIPH_RANGEFINDER_ENABLED = 1,
AP_PERIPH_BATTERY_ENABLED = 1,
AP_PERIPH_BATTERY_BALANCE_ENABLED = 0,
HAL_PERIPH_ENABLE_EFI = 1,
Expand Down

0 comments on commit 1306136

Please sign in to comment.