AP_HAL_Linux: Improve loading firmware

This commit is contained in:
mirkix 2015-11-12 20:56:50 +01:00
parent 4f7246c432
commit f00d4f0b3e

View File

@ -51,13 +51,12 @@ void RCOutput_AioPRU::init(void* machtnicht)
// Reset PRU 1
*ctrl = 0;
hal.scheduler->delay(1);
// Load firmware
memcpy(iram, PRUcode, sizeof(PRUcode));
// Start PRU 1
*ctrl = 3;
*ctrl |= 2;
// all outputs default to 50Hz, the top level vehicle code
// overrides this when necessary