mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_IOMCU: added blue LED support on PH1
This commit is contained in:
parent
19c002baaf
commit
89bfd7e850
@ -154,13 +154,15 @@ static UARTConfig uart_cfg = {
|
||||
|
||||
void setup(void)
|
||||
{
|
||||
hal.gpio->init();
|
||||
hal.rcin->init();
|
||||
hal.rcout->init();
|
||||
|
||||
for (uint8_t i = 0; i< 14; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
}
|
||||
|
||||
iomcu.init();
|
||||
|
||||
iomcu.calculate_fw_crc();
|
||||
uartStart(&UARTD2, &uart_cfg);
|
||||
uartStartReceive(&UARTD2, sizeof(iomcu.rx_io_packet), &iomcu.rx_io_packet);
|
||||
@ -171,6 +173,14 @@ void loop(void)
|
||||
iomcu.update();
|
||||
}
|
||||
|
||||
void AP_IOMCU_FW::init()
|
||||
{
|
||||
if (palReadLine(HAL_GPIO_PIN_IO_HW_DETECT1) == 1 && palReadLine(HAL_GPIO_PIN_IO_HW_DETECT2) == 0) {
|
||||
has_heater = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void AP_IOMCU_FW::update()
|
||||
{
|
||||
if (do_reboot && (AP_HAL::millis() > reboot_time)) {
|
||||
@ -195,11 +205,18 @@ void AP_IOMCU_FW::pwm_out_update()
|
||||
|
||||
void AP_IOMCU_FW::heater_update()
|
||||
{
|
||||
if (reg_setup.heater_duty_cycle == 0 || (AP_HAL::millis() - last_heater_ms > 3000UL)) {
|
||||
hal.gpio->write(0, 0);
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (!has_heater) {
|
||||
// use blue LED as heartbeat
|
||||
if (now - last_blue_led_ms > 500) {
|
||||
palToggleLine(HAL_GPIO_PIN_HEATER);
|
||||
last_blue_led_ms = now;
|
||||
}
|
||||
} else if (reg_setup.heater_duty_cycle == 0 || (now - last_heater_ms > 3000UL)) {
|
||||
palWriteLine(HAL_GPIO_PIN_HEATER, 0);
|
||||
} else {
|
||||
uint8_t cycle = ((AP_HAL::millis() / 10UL) % 100U);
|
||||
hal.gpio->write(0, !(cycle >= reg_setup.heater_duty_cycle));
|
||||
uint8_t cycle = ((now / 10UL) % 100U);
|
||||
palWriteLine(HAL_GPIO_PIN_HEATER, !(cycle >= reg_setup.heater_duty_cycle));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -25,6 +25,7 @@ public:
|
||||
}
|
||||
} rx_io_packet = {0}, tx_io_packet = {0};
|
||||
|
||||
void init();
|
||||
void update();
|
||||
void calculate_fw_crc(void);
|
||||
|
||||
@ -137,5 +138,7 @@ private:
|
||||
bool do_reboot;
|
||||
bool update_default_rate;
|
||||
bool update_rcout_freq;
|
||||
};
|
||||
bool has_heater;
|
||||
uint32_t last_blue_led_ms;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user