Skip to content

Commit

Permalink
Tools: create and use AP_PERIPH_BARO_ENABLED
Browse files Browse the repository at this point in the history
  • Loading branch information
shiv-tyagi authored and peterbarker committed Jan 30, 2025
1 parent 4fca0cc commit dba4136
Show file tree
Hide file tree
Showing 8 changed files with 14 additions and 14 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 @@ -164,7 +164,7 @@ void AP_Periph_FW::init()
compass.init();
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
baro.init();
#endif

Expand Down Expand Up @@ -429,7 +429,7 @@ void AP_Periph_FW::update()
const Vector3f &field = compass.get_field();
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#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
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 @@ -231,7 +231,7 @@ class AP_Periph_FW {
Compass compass;
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Baro baro;
#endif

Expand Down Expand Up @@ -457,7 +457,7 @@ class AP_Periph_FW {
uint32_t last_gps_yaw_ms;
#endif
uint32_t last_relposheading_ms;
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
uint32_t last_baro_update_ms;
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
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 @@ -269,7 +269,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(compass, "COMPASS_", Compass),
#endif

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
// Baro driver
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
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 @@ -119,7 +119,7 @@ class Parameters {
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
AP_Int8 led_brightness;
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Int8 baro_enable;
#endif
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
Expand Down
4 changes: 2 additions & 2 deletions Tools/AP_Periph/baro.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED

/*
barometer support
Expand Down Expand Up @@ -60,4 +60,4 @@ void AP_Periph_FW::can_baro_update(void)
}
}

#endif // HAL_PERIPH_ENABLE_BARO
#endif // AP_PERIPH_BARO_ENABLED
4 changes: 2 additions & 2 deletions Tools/AP_Periph/can.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
#if AP_PERIPH_MAG_ENABLED
AP_Param::setup_object_defaults(&compass, compass.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
AP_Param::setup_object_defaults(&baro, baro.var_info);
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down Expand Up @@ -1894,7 +1894,7 @@ void AP_Periph_FW::can_update()
#if AP_PERIPH_BATTERY_ENABLED
can_battery_update();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
can_baro_update();
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
Expand Down
6 changes: 3 additions & 3 deletions Tools/AP_Periph/msp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ void AP_Periph_FW::msp_sensor_update(void)
#if AP_PERIPH_GPS_ENABLED
send_msp_GPS();
#endif
#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
send_msp_baro();
#endif
#if AP_PERIPH_MAG_ENABLED
Expand Down Expand Up @@ -125,7 +125,7 @@ void AP_Periph_FW::send_msp_GPS(void)
#endif // AP_PERIPH_GPS_ENABLED


#ifdef HAL_PERIPH_ENABLE_BARO
#if AP_PERIPH_BARO_ENABLED
/*
send MSP baro packet
*/
Expand All @@ -149,7 +149,7 @@ void AP_Periph_FW::send_msp_baro(void)

send_msp_packet(MSP2_SENSOR_BAROMETER, &p, sizeof(p));
}
#endif // HAL_PERIPH_ENABLE_BARO
#endif // AP_PERIPH_BARO_ENABLED

#if AP_PERIPH_MAG_ENABLED
/*
Expand Down
2 changes: 1 addition & 1 deletion Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -955,7 +955,7 @@ def configure_env(self, cfg, env):
AP_PERIPH_GPS_ENABLED = 1,
HAL_PERIPH_ENABLE_AIRSPEED = 1,
AP_PERIPH_MAG_ENABLED = 1,
HAL_PERIPH_ENABLE_BARO = 1,
AP_PERIPH_BARO_ENABLED = 1,
HAL_PERIPH_ENABLE_IMU = 1,
HAL_PERIPH_ENABLE_RANGEFINDER = 1,
AP_PERIPH_BATTERY_ENABLED = 1,
Expand Down

0 comments on commit dba4136

Please sign in to comment.