AP_Periph: rename AP_PERIPH_<feature>_DEFAULT to HAL_PERIPH_<feature>_DEFAULT

This commit is contained in:
Tom Pittenger 2020-12-26 12:18:08 -07:00 committed by Andrew Tridgell
parent 80b3c2491f
commit 71859c9893
1 changed files with 9 additions and 9 deletions

View File

@ -2,16 +2,16 @@
extern const AP_HAL::HAL &hal;
#ifndef AP_PERIPH_LED_BRIGHT_DEFAULT
#define AP_PERIPH_LED_BRIGHT_DEFAULT 100
#ifndef HAL_PERIPH_LED_BRIGHT_DEFAULT
#define HAL_PERIPH_LED_BRIGHT_DEFAULT 100
#endif
#ifndef AP_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT
#define AP_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
#ifndef HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT
#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
#endif
#ifndef AP_PERIPH_RANGEFINDER_PORT_DEFAULT
#define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
#ifndef HAL_PERIPH_RANGEFINDER_PORT_DEFAULT
#define HAL_PERIPH_RANGEFINDER_PORT_DEFAULT 3
#endif
#ifndef HAL_PERIPH_GPS_PORT_DEFAULT
@ -99,7 +99,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif
#ifdef AP_PERIPH_HAVE_LED
GSCALAR(led_brightness, "LED_BRIGHTNESS", AP_PERIPH_LED_BRIGHT_DEFAULT),
GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),
#endif
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
@ -110,8 +110,8 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
GSCALAR(rangefinder_baud, "RNGFND_BAUDRATE", AP_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
GSCALAR(rangefinder_port, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),
GSCALAR(rangefinder_baud, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
GSCALAR(rangefinder_port, "RNGFND_PORT", HAL_PERIPH_RANGEFINDER_PORT_DEFAULT),
// Rangefinder driver
// @Group: RNGFND