AP_IOMCU: use macros for LED outputs in iofirmware

This commit is contained in:
Andrew Tridgell 2018-11-01 18:24:41 +11:00
parent a8d91a24b6
commit 29fb674f3f
3 changed files with 22 additions and 10 deletions

View File

@ -169,7 +169,7 @@ void AP_IOMCU_FW::init()
// power on spektrum port
palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL);
palSetLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN);
SPEKTRUM_POWER(1);
rcprotocol = AP_RCProtocol::get_instance();
@ -217,8 +217,12 @@ void AP_IOMCU_FW::update()
chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM));
last_failsafe_ms = now;
}
// turn amber on
AMBER_SET(1);
} else {
last_failsafe_ms = now;
// turn amber off
AMBER_SET(0);
}
// update status page at 20Hz
@ -262,14 +266,15 @@ void AP_IOMCU_FW::heater_update()
if (!has_heater) {
// use blue LED as heartbeat, run it 4x faster when override active
if (now - last_blue_led_ms > (override_active?125:500)) {
palToggleLine(HAL_GPIO_PIN_HEATER);
BLUE_TOGGLE();
last_blue_led_ms = now;
}
} else if (reg_setup.heater_duty_cycle == 0 || (now - last_heater_ms > 3000UL)) {
palWriteLine(HAL_GPIO_PIN_HEATER, 0);
// turn off the heater
HEATER_SET(0);
} else {
uint8_t cycle = ((now / 10UL) % 100U);
palWriteLine(HAL_GPIO_PIN_HEATER, !(cycle >= reg_setup.heater_duty_cycle));
HEATER_SET(!(cycle >= reg_setup.heater_duty_cycle));
}
}

View File

@ -139,3 +139,10 @@ private:
uint32_t last_failsafe_ms;
};
// GPIO macros
#define HEATER_SET(on) palWriteLine(HAL_GPIO_PIN_HEATER, !(on));
#define BLUE_TOGGLE() palToggleLine(HAL_GPIO_PIN_HEATER);
#define AMBER_SET(on) palWriteLine(HAL_GPIO_PIN_AMBER_LED, !(on));
#define SPEKTRUM_POWER(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, on);
#define SPEKTRUM_SET(on) palWriteLine(HAL_GPIO_PIN_SPEKTRUM_OUT, on);

View File

@ -82,7 +82,7 @@ void AP_IOMCU_FW::rcin_serial_update(void)
for (uint8_t i=0; i<n; i++) {
rcprotocol->process_byte(b[i]);
}
//palToggleLine(HAL_GPIO_PIN_HEATER);
//BLUE_TOGGLE();
}
}
@ -104,16 +104,16 @@ void AP_IOMCU_FW::dsm_bind_step(void)
switch (dsm_bind_state) {
case 1:
palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL);
palClearLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN);
SPEKTRUM_POWER(0);
palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_OUT, PAL_MODE_OUTPUT_PUSHPULL);
palSetLine(HAL_GPIO_PIN_SPEKTRUM_OUT);
SPEKTRUM_SET(1);
dsm_bind_state = 2;
last_dsm_bind_ms = now;
break;
case 2:
if (now - last_dsm_bind_ms >= 500) {
palSetLine(HAL_GPIO_PIN_SPEKTRUM_PWR_EN);
SPEKTRUM_POWER(1);
dsm_bind_state = 3;
last_dsm_bind_ms = now;
}
@ -129,9 +129,9 @@ void AP_IOMCU_FW::dsm_bind_step(void)
// the delay should be 120us, but we are running our
// clock at 1kHz, and 1ms works fine
delay_one_ms(now);
palClearLine(HAL_GPIO_PIN_SPEKTRUM_OUT);
SPEKTRUM_SET(0);
delay_one_ms(now);
palSetLine(HAL_GPIO_PIN_SPEKTRUM_OUT);
SPEKTRUM_SET(1);
}
last_dsm_bind_ms = now;
dsm_bind_state = 4;