AP_IOMCU: support brushed output

This commit is contained in:
Andrew Tridgell 2018-07-13 14:44:16 +10:00
parent cfb10fbb2f
commit f0b27c9b92
3 changed files with 15 additions and 7 deletions

View File

@ -330,13 +330,6 @@ bool AP_IOMCU_FW::handle_code_write()
}
break;
case PAGE_REG_SETUP_ALTRATE:
if (rx_io_packet.regs[0] < 25 && reg_setup.pwm_altclock == 1) {
rx_io_packet.regs[0] = 25;
}
if (rx_io_packet.regs[0] > 400 && reg_setup.pwm_altclock == 1) {
rx_io_packet.regs[0] = 400;
}
reg_setup.pwm_altrate = rx_io_packet.regs[0];
update_rcout_freq = true;
break;
@ -488,6 +481,19 @@ void AP_IOMCU_FW::rcout_mode_update(void)
oneshot_enabled = true;
hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
}
bool use_brushed = (reg_setup.features & P_SETUP_FEATURES_BRUSHED) != 0;
if (use_brushed && !brushed_enabled) {
brushed_enabled = true;
if (reg_setup.pwm_rates == 0) {
// default to 2kHz for all channels for brushed output
reg_setup.pwm_rates = 0xFF;
reg_setup.pwm_altrate = 2000;
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
}
hal.rcout->set_esc_scaling(1000, 2000);
hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
}
}
AP_HAL_MAIN();

View File

@ -94,6 +94,7 @@ private:
uint8_t led_counter;
uint32_t last_loop_ms;
bool oneshot_enabled;
bool brushed_enabled;
thread_t *thread_ctx;
bool last_safety_off;
};

View File

@ -58,6 +58,7 @@ enum iopage {
#define P_SETUP_FEATURES_PWM_RSSI 4
#define P_SETUP_FEATURES_ADC_RSSI 8
#define P_SETUP_FEATURES_ONESHOT 16
#define P_SETUP_FEATURES_BRUSHED 32
#define PAGE_REG_SETUP_ARMING 1
#define P_SETUP_ARMING_IO_ARM_OK (1<<0)