AP_IOMCU: add support for iofirmware update

This commit is contained in:
Siddharth Purohit 2018-05-05 23:46:52 +05:30 committed by Andrew Tridgell
parent 746ed2be79
commit 19c002baaf
3 changed files with 100 additions and 19 deletions

View File

@ -711,6 +711,8 @@ bool AP_IOMCU::check_crc(void)
free(fw);
fw = nullptr;
return true;
} else {
hal.console->printf("IOMCU: CRC mismatch expected: 0x%X got: 0x%X\n", crc, io_crc);
}
const uint16_t magic = REBOOT_BL_MAGIC;

View File

@ -1,6 +1,4 @@
//
// Simple test for the AP_AHRS interface
//
//IO Controller Firmware
#include <AP_HAL/AP_HAL.h>
@ -56,13 +54,14 @@ enum iopage {
#define PAGE_REG_SETUP_PWM_RATE_MASK 2
#define PAGE_REG_SETUP_DEFAULTRATE 3
#define PAGE_REG_SETUP_ALTRATE 4
#define PAGE_REG_SETUP_REBOOT_BL 10
#define PAGE_REG_SETUP_SBUS_RATE 19
#define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21
#define PAGE_REG_SETUP_FORCE_SAFETY_OFF 12
#define PAGE_REG_SETUP_FORCE_SAFETY_ON 14
#define FORCE_SAFETY_MAGIC 22027
#define FORCE_SAFETY_MAGIC 22027
#define PX4IO_REBOOT_BL_MAGIC 14662
void setup();
void loop();
@ -104,11 +103,14 @@ void dma_rx_end_cb(UARTDriver *uart)
void idle_rx_handler(UARTDriver *uart) {
volatile uint16_t sr = uart->usart->SR;
if (sr & (USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
if (sr & (USART_SR_LBD | USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
USART_SR_NE | /* noise error - we have lost a byte due to noise */
USART_SR_FE)) { /* framing error - start/stop bit lost or line break */
USART_SR_FE |
USART_SR_PE)) { /* framing error - start/stop bit lost or line break */
/* send a line break - this will abort transmission/reception on the other end */
osalSysLockFromISR();
uart->usart->SR = ~USART_SR_LBD;
uart->usart->CR1 |= USART_CR1_SBK;
num_rx_error++;
uart->usart->CR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
@ -159,16 +161,25 @@ void setup(void)
for (uint8_t i = 0; i< 14; i++) {
hal.rcout->enable_ch(i);
}
(void)uart_cfg;
iomcu.calculate_fw_crc();
uartStart(&UARTD2, &uart_cfg);
uartStartReceive(&UARTD2, sizeof(iomcu.rx_io_packet), &iomcu.rx_io_packet);
}
void loop(void)
{
iomcu.pwm_out_update();
iomcu.heater_update();
iomcu.rcin_update();
iomcu.update();
}
void AP_IOMCU_FW::update()
{
if (do_reboot && (AP_HAL::millis() > reboot_time)) {
hal.scheduler->reboot(true);
while(true){}
}
pwm_out_update();
heater_update();
rcin_update();
}
void AP_IOMCU_FW::pwm_out_update()
@ -202,6 +213,14 @@ void AP_IOMCU_FW::rcin_update()
}
rc_input.last_input_us = AP_HAL::micros();
}
if (update_rcout_freq) {
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
update_rcout_freq = false;
}
if (update_default_rate) {
hal.rcout->set_default_rate(reg_setup.pwm_defaultrate);
}
}
void AP_IOMCU_FW::process_io_packet()
@ -222,13 +241,25 @@ void AP_IOMCU_FW::process_io_packet()
case CODE_READ:
{
num_code_read++;
handle_code_read();
if(!handle_code_read()) {
memset(&tx_io_packet, 0xFF, sizeof(tx_io_packet));
tx_io_packet.count = 0;
tx_io_packet.code = CODE_ERROR;
tx_io_packet.crc = 0;
tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
}
}
break;
case CODE_WRITE:
{
num_write_pkt++;
handle_code_write();
if(!handle_code_write()) {
memset(&tx_io_packet, 0xFF, sizeof(tx_io_packet));
tx_io_packet.count = 0;
tx_io_packet.code = CODE_ERROR;
tx_io_packet.crc = 0;
tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
}
}
break;
default:
@ -312,11 +343,11 @@ bool AP_IOMCU_FW::handle_code_write()
rx_io_packet.regs[0] = 400;
}
reg_setup.pwm_altrate = rx_io_packet.regs[0];
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
update_rcout_freq = true;
break;
case PAGE_REG_SETUP_PWM_RATE_MASK:
reg_setup.pwm_rates = rx_io_packet.regs[0];
hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
update_rcout_freq = true;
break;
case PAGE_REG_SETUP_DEFAULTRATE:
if (rx_io_packet.regs[0] < 25 && reg_setup.pwm_altclock == 1) {
@ -327,7 +358,7 @@ bool AP_IOMCU_FW::handle_code_write()
rx_io_packet.regs[0] = 400;
}
reg_setup.pwm_defaultrate = rx_io_packet.regs[0];
hal.rcout->set_default_rate(reg_setup.pwm_defaultrate);
update_default_rate = true;
break;
case PAGE_REG_SETUP_SBUS_RATE:
break;
@ -344,6 +375,20 @@ bool AP_IOMCU_FW::handle_code_write()
reg_setup.heater_duty_cycle = rx_io_packet.regs[0];
last_heater_ms = AP_HAL::millis();
break;
case PAGE_REG_SETUP_REBOOT_BL:
if (reg_status.flag_safety_off) {
// don't allow reboot while armed
return false;
}
// check the magic value
if (rx_io_packet.regs[0] != PX4IO_REBOOT_BL_MAGIC) {
return false;
}
schedule_reboot(100);
break;
default:
break;
}
@ -368,6 +413,7 @@ bool AP_IOMCU_FW::handle_code_write()
//TODO: Oneshot support
break;
}
default:
break;
}
@ -379,4 +425,26 @@ bool AP_IOMCU_FW::handle_code_write()
return true;
}
void AP_IOMCU_FW::schedule_reboot(uint32_t time_ms)
{
do_reboot = true;
reboot_time = AP_HAL::millis() + time_ms;
}
void AP_IOMCU_FW::calculate_fw_crc(void)
{
#define APP_SIZE_MAX 0xf000
#define APP_LOAD_ADDRESS 0x08001000
// compute CRC of the current firmware
uint32_t sum = 0;
for (unsigned p = 0; p < APP_SIZE_MAX; p += 4) {
uint32_t bytes = *(uint32_t *)(p + APP_LOAD_ADDRESS);
sum = crc_crc32(sum, (const uint8_t *)&bytes, sizeof(bytes));
}
reg_setup.crc[0] = sum & 0xFFFF;
reg_setup.crc[1] = sum >> 16;
}
AP_HAL_MAIN();

View File

@ -25,13 +25,17 @@ public:
}
} rx_io_packet = {0}, tx_io_packet = {0};
void update();
void calculate_fw_crc(void);
private:
void pwm_out_update();
void heater_update();
void rcin_update();
private:
bool handle_code_write();
bool handle_code_read();
void schedule_reboot(uint32_t time_ms);
struct PACKED {
/* default to RSSI ADC functionality */
uint16_t features = 0;
@ -39,17 +43,20 @@ private:
uint16_t pwm_rates = 0;
uint16_t pwm_defaultrate = 50;
uint16_t pwm_altrate = 200;
uint16_t sbus_rate = 72;
uint16_t relays_pad = 0;
uint16_t vbatt_scale = 10000;
uint16_t reserved1;
uint16_t reserved2;
uint16_t set_debug = 0;
uint16_t reboot_bl = 0;
uint16_t crc[2] = {0};
uint16_t rc_thr_failsafe_us;
uint16_t reserved3;
uint16_t pwm_reverse = 0;
uint16_t trim_roll = 0;
uint16_t trim_pitch = 0;
uint16_t trim_yaw = 0;
uint16_t sbus_rate = 72;
uint16_t ignore_safety = 0;
uint16_t heater_duty_cycle = 0xFFFFU;
uint16_t pwm_altclock = 1;
@ -126,5 +133,9 @@ private:
uint8_t last_offset;
uint32_t fmu_data_received_time;
uint32_t last_heater_ms;
uint32_t reboot_time;
bool do_reboot;
bool update_default_rate;
bool update_rcout_freq;
};