AP_HAL_ChibiOS: move defaulting of HAL_DSHOT_ALARM into hwdef
This commit is contained in:
parent
3d63a968cf
commit
28a0336423
@ -29,7 +29,7 @@
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
#include "sdcard.h"
|
||||
#include "shared_dma.h"
|
||||
#if defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM || HAL_CANMANAGER_ENABLED || HAL_USE_PWM == TRUE
|
||||
#if defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM_ENABLED || HAL_CANMANAGER_ENABLED || HAL_USE_PWM == TRUE
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#endif
|
||||
#if HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
@ -171,7 +171,7 @@ bool Util::toneAlarm_init(uint8_t types)
|
||||
#endif
|
||||
_toneAlarm_types = types;
|
||||
|
||||
#if HAL_USE_PWM != TRUE && !HAL_DSHOT_ALARM && !HAL_CANMANAGER_ENABLED
|
||||
#if HAL_USE_PWM != TRUE && !HAL_DSHOT_ALARM_ENABLED && !HAL_CANMANAGER_ENABLED
|
||||
// Nothing to do
|
||||
return false;
|
||||
#else
|
||||
@ -209,7 +209,7 @@ void Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t dur
|
||||
}
|
||||
}
|
||||
#endif // HAL_USE_PWM
|
||||
#if HAL_DSHOT_ALARM
|
||||
#if HAL_DSHOT_ALARM_ENABLED
|
||||
// don't play the motors while flying
|
||||
if (!(_toneAlarm_types & AP_Notify::Notify_Buzz_DShot) || get_soft_armed() || hal.rcout->get_dshot_esc_type() != RCOutput::DSHOT_ESC_BLHELI) {
|
||||
return;
|
||||
@ -228,7 +228,7 @@ void Util::toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t dur
|
||||
} else { // G+
|
||||
hal.rcout->send_dshot_command(RCOutput::DSHOT_BEEP5, RCOutput::ALL_CHANNELS, duration_ms);
|
||||
}
|
||||
#endif // HAL_DSHOT_ALARM
|
||||
#endif // HAL_DSHOT_ALARM_ENABLED
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -2345,6 +2345,9 @@ def write_hwdef_header(outfilename):
|
||||
write_AIRSPEED_config(f)
|
||||
write_board_validate_macro(f)
|
||||
add_apperiph_defaults(f)
|
||||
add_bootloader_defaults(f)
|
||||
add_iomcu_firmware_defaults(f)
|
||||
add_normal_firmware_defaults(f)
|
||||
write_check_firmware(f)
|
||||
|
||||
write_peripheral_enable(f)
|
||||
@ -2784,6 +2787,8 @@ def add_apperiph_defaults(f):
|
||||
|
||||
print("Setting up as AP_Periph")
|
||||
f.write('''
|
||||
// AP_Periph defaults
|
||||
|
||||
#ifndef HAL_SCHEDULER_ENABLED
|
||||
#define HAL_SCHEDULER_ENABLED 0
|
||||
#endif
|
||||
@ -2913,6 +2918,51 @@ def add_apperiph_defaults(f):
|
||||
|
||||
''')
|
||||
|
||||
def add_bootloader_defaults(f):
|
||||
'''add default defines for peripherals'''
|
||||
if not args.bootloader:
|
||||
return
|
||||
|
||||
print("Setting up as Bootloader")
|
||||
f.write('''
|
||||
// AP_Bootloader defaults
|
||||
|
||||
#define HAL_DSHOT_ALARM_ENABLED 0
|
||||
''')
|
||||
|
||||
def add_iomcu_firmware_defaults(f):
|
||||
'''add default defines IO firmwares'''
|
||||
if env_vars.get('IOMCU_FW', 0) == 0:
|
||||
# not IOMCU firmware
|
||||
return
|
||||
|
||||
print("Setting up as IO firmware")
|
||||
f.write('''
|
||||
// IOMCU Firmware defaults
|
||||
|
||||
#define HAL_DSHOT_ALARM_ENABLED 0
|
||||
''')
|
||||
|
||||
def add_normal_firmware_defaults(f):
|
||||
'''add default defines to builds with are not bootloader, periph or IOMCU'''
|
||||
if env_vars.get('IOMCU_FW', 0) != 0:
|
||||
# IOMCU firmware
|
||||
return
|
||||
if env_vars.get('AP_PERIPH', 0) != 0:
|
||||
# Periph firmware
|
||||
return
|
||||
if args.bootloader:
|
||||
# guess
|
||||
return
|
||||
|
||||
print("Setting up as normal firmware")
|
||||
f.write('''
|
||||
// firmware defaults
|
||||
|
||||
#ifndef HAL_DSHOT_ALARM_ENABLED
|
||||
#define HAL_DSHOT_ALARM_ENABLED (HAL_PWM_COUNT>0)
|
||||
#endif
|
||||
''')
|
||||
|
||||
# process input file
|
||||
for fname in args.hwdef:
|
||||
|
Loading…
Reference in New Issue
Block a user