mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_BoardConfig: fixed typo in volt pin handling
This commit is contained in:
parent
4bdc18569e
commit
49efe539fc
@ -225,7 +225,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
// @Param: PWM_VOLT_SEL
|
||||
// @DisplayName: Set PWM Out Voltage
|
||||
// @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output.
|
||||
//@Values: 0:3.3V,1:5V
|
||||
// @Values: 0:3.3V,1:5V
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),
|
||||
#endif
|
||||
|
@ -346,7 +346,7 @@ void AP_BoardConfig::board_setup()
|
||||
hal.rcout->init();
|
||||
#endif
|
||||
|
||||
#if HAL_GPIO_PWM_VOLT_PIN
|
||||
#ifdef HAL_GPIO_PWM_VOLT_PIN
|
||||
if (_pwm_volt_sel == 0) {
|
||||
hal.gpio->write(HAL_GPIO_PWM_VOLT_PIN, 1); //set pin for 3.3V PWM Output
|
||||
} else if (_pwm_volt_sel == 1) {
|
||||
|
Loading…
Reference in New Issue
Block a user