mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
Tools: replace HAL_PERIPH_ENABLE_AIRSPEED with AP_PERIPH_AIRSPEED_ENABLED
This commit is contained in:
parent
fb8f3488d5
commit
0248f0d5d8
@ -216,7 +216,7 @@ void AP_Periph_FW::init()
|
||||
kdecan.init();
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && (HAL_USE_I2C == TRUE)
|
||||
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
|
||||
if (pins_enabled) {
|
||||
|
@ -294,7 +294,7 @@ public:
|
||||
} adsb;
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
AP_Airspeed airspeed;
|
||||
#endif
|
||||
|
||||
@ -460,7 +460,7 @@ public:
|
||||
#if AP_PERIPH_BARO_ENABLED
|
||||
uint32_t last_baro_update_ms;
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
uint32_t last_airspeed_update_ms;
|
||||
#endif
|
||||
#if AP_PERIPH_GPS_ENABLED
|
||||
|
@ -294,7 +294,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
||||
GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
// Airspeed driver
|
||||
// @Group: ARSPD
|
||||
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "AP_Periph.h"
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
|
||||
/*
|
||||
airspeed support
|
||||
@ -82,4 +82,4 @@ void AP_Periph_FW::can_airspeed_update(void)
|
||||
total_size);
|
||||
}
|
||||
|
||||
#endif // HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#endif // AP_PERIPH_AIRSPEED_ENABLED
|
||||
|
@ -358,7 +358,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C
|
||||
#if AP_PERIPH_BARO_ENABLED
|
||||
AP_Param::setup_object_defaults(&baro, baro.var_info);
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);
|
||||
#endif
|
||||
#if AP_PERIPH_RANGEFINDER_ENABLED
|
||||
@ -1927,7 +1927,7 @@ void AP_Periph_FW::can_update()
|
||||
#if AP_PERIPH_BARO_ENABLED
|
||||
can_baro_update();
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
can_airspeed_update();
|
||||
#endif
|
||||
#if AP_PERIPH_RANGEFINDER_ENABLED
|
||||
|
@ -54,7 +54,7 @@ void AP_Periph_FW::msp_sensor_update(void)
|
||||
#if AP_PERIPH_MAG_ENABLED
|
||||
send_msp_compass();
|
||||
#endif
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
send_msp_airspeed();
|
||||
#endif
|
||||
}
|
||||
@ -178,7 +178,7 @@ void AP_Periph_FW::send_msp_compass(void)
|
||||
}
|
||||
#endif // AP_PERIPH_MAG_ENABLED
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#if AP_PERIPH_AIRSPEED_ENABLED
|
||||
/*
|
||||
send MSP airspeed packet
|
||||
*/
|
||||
@ -209,7 +209,7 @@ void AP_Periph_FW::send_msp_airspeed(void)
|
||||
|
||||
send_msp_packet(MSP2_SENSOR_AIRSPEED, &p, sizeof(p));
|
||||
}
|
||||
#endif // HAL_PERIPH_ENABLE_AIRSPEED
|
||||
#endif // AP_PERIPH_AIRSPEED_ENABLED
|
||||
|
||||
|
||||
#endif // HAL_PERIPH_ENABLE_MSP
|
||||
|
@ -953,7 +953,7 @@ class sitl_periph_universal(sitl_periph):
|
||||
APJ_BOARD_ID = 100,
|
||||
|
||||
AP_PERIPH_GPS_ENABLED = 1,
|
||||
HAL_PERIPH_ENABLE_AIRSPEED = 1,
|
||||
AP_PERIPH_AIRSPEED_ENABLED = 1,
|
||||
AP_PERIPH_MAG_ENABLED = 1,
|
||||
AP_PERIPH_BARO_ENABLED = 1,
|
||||
AP_PERIPH_IMU_ENABLED = 1,
|
||||
@ -999,6 +999,7 @@ class sitl_periph_gps(sitl_periph):
|
||||
AP_PERIPH_RCIN_ENABLED = 0,
|
||||
AP_PERIPH_RPM_ENABLED = 0,
|
||||
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
||||
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
||||
)
|
||||
|
||||
class sitl_periph_battmon(sitl_periph):
|
||||
@ -1022,6 +1023,7 @@ class sitl_periph_battmon(sitl_periph):
|
||||
AP_PERIPH_RCIN_ENABLED = 0,
|
||||
AP_PERIPH_RPM_ENABLED = 0,
|
||||
AP_PERIPH_RPM_STREAM_ENABLED = 0,
|
||||
AP_PERIPH_AIRSPEED_ENABLED = 0,
|
||||
)
|
||||
|
||||
class esp32(Board):
|
||||
|
Loading…
Reference in New Issue
Block a user