iofirmware.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. IOMCU main firmware
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <AP_Math/crc.h>
  19. #include "iofirmware.h"
  20. #include "hal.h"
  21. #include <AP_HAL_ChibiOS/RCInput.h>
  22. #include <AP_HAL_ChibiOS/RCOutput.h>
  23. #include "analog.h"
  24. #include "rc.h"
  25. #include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
  26. extern const AP_HAL::HAL &hal;
  27. // we build this file with optimisation to lower the interrupt
  28. // latency. This helps reduce the chance of losing an RC input byte
  29. // due to missing a UART interrupt
  30. #pragma GCC optimize("O2")
  31. static AP_IOMCU_FW iomcu;
  32. void setup();
  33. void loop();
  34. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  35. // enable testing of IOMCU watchdog using safety switch
  36. #define IOMCU_ENABLE_WATCHDOG_TEST 0
  37. // pending events on the main thread
  38. enum ioevents {
  39. IOEVENT_PWM=1,
  40. };
  41. static void dma_rx_end_cb(UARTDriver *uart)
  42. {
  43. osalSysLockFromISR();
  44. uart->usart->CR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
  45. (void)uart->usart->SR;
  46. (void)uart->usart->DR;
  47. (void)uart->usart->DR;
  48. dmaStreamDisable(uart->dmarx);
  49. dmaStreamDisable(uart->dmatx);
  50. iomcu.process_io_packet();
  51. dmaStreamSetMemory0(uart->dmarx, &iomcu.rx_io_packet);
  52. dmaStreamSetTransactionSize(uart->dmarx, sizeof(iomcu.rx_io_packet));
  53. dmaStreamSetMode(uart->dmarx, uart->dmamode | STM32_DMA_CR_DIR_P2M |
  54. STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
  55. dmaStreamEnable(uart->dmarx);
  56. uart->usart->CR3 |= USART_CR3_DMAR;
  57. dmaStreamSetMemory0(uart->dmatx, &iomcu.tx_io_packet);
  58. dmaStreamSetTransactionSize(uart->dmatx, iomcu.tx_io_packet.get_size());
  59. dmaStreamSetMode(uart->dmatx, uart->dmamode | STM32_DMA_CR_DIR_M2P |
  60. STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
  61. dmaStreamEnable(uart->dmatx);
  62. uart->usart->CR3 |= USART_CR3_DMAT;
  63. osalSysUnlockFromISR();
  64. }
  65. static void idle_rx_handler(UARTDriver *uart)
  66. {
  67. volatile uint16_t sr = uart->usart->SR;
  68. if (sr & (USART_SR_LBD | USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
  69. USART_SR_NE | /* noise error - we have lost a byte due to noise */
  70. USART_SR_FE |
  71. USART_SR_PE)) { /* framing error - start/stop bit lost or line break */
  72. /* send a line break - this will abort transmission/reception on the other end */
  73. osalSysLockFromISR();
  74. uart->usart->SR = ~USART_SR_LBD;
  75. uart->usart->CR1 |= USART_CR1_SBK;
  76. iomcu.reg_status.num_errors++;
  77. iomcu.reg_status.err_uart++;
  78. uart->usart->CR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
  79. (void)uart->usart->SR;
  80. (void)uart->usart->DR;
  81. (void)uart->usart->DR;
  82. dmaStreamDisable(uart->dmarx);
  83. dmaStreamDisable(uart->dmatx);
  84. dmaStreamSetMemory0(uart->dmarx, &iomcu.rx_io_packet);
  85. dmaStreamSetTransactionSize(uart->dmarx, sizeof(iomcu.rx_io_packet));
  86. dmaStreamSetMode(uart->dmarx, uart->dmamode | STM32_DMA_CR_DIR_P2M |
  87. STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
  88. dmaStreamEnable(uart->dmarx);
  89. uart->usart->CR3 |= USART_CR3_DMAR;
  90. osalSysUnlockFromISR();
  91. return;
  92. }
  93. if (sr & USART_SR_IDLE) {
  94. dma_rx_end_cb(uart);
  95. }
  96. }
  97. /*
  98. * UART driver configuration structure.
  99. */
  100. static UARTConfig uart_cfg = {
  101. nullptr,
  102. nullptr,
  103. dma_rx_end_cb,
  104. nullptr,
  105. nullptr,
  106. idle_rx_handler,
  107. 1500000, //1.5MBit
  108. USART_CR1_IDLEIE,
  109. 0,
  110. 0
  111. };
  112. void setup(void)
  113. {
  114. hal.rcin->init();
  115. hal.rcout->init();
  116. for (uint8_t i = 0; i< 14; i++) {
  117. hal.rcout->enable_ch(i);
  118. }
  119. iomcu.init();
  120. iomcu.calculate_fw_crc();
  121. uartStart(&UARTD2, &uart_cfg);
  122. uartStartReceive(&UARTD2, sizeof(iomcu.rx_io_packet), &iomcu.rx_io_packet);
  123. }
  124. void loop(void)
  125. {
  126. iomcu.update();
  127. }
  128. void AP_IOMCU_FW::init()
  129. {
  130. // the first protocol version must be 4 to allow downgrade to
  131. // old NuttX based firmwares
  132. config.protocol_version = IOMCU_PROTOCOL_VERSION;
  133. config.protocol_version2 = IOMCU_PROTOCOL_VERSION2;
  134. thread_ctx = chThdGetSelfX();
  135. if (palReadLine(HAL_GPIO_PIN_IO_HW_DETECT1) == 1 && palReadLine(HAL_GPIO_PIN_IO_HW_DETECT2) == 0) {
  136. has_heater = true;
  137. }
  138. //Set Heater pin mode
  139. if (heater_pwm_polarity) {
  140. palSetLineMode(HAL_GPIO_PIN_HEATER, PAL_MODE_OUTPUT_PUSHPULL);
  141. } else {
  142. palSetLineMode(HAL_GPIO_PIN_HEATER, PAL_MODE_OUTPUT_OPENDRAIN);
  143. }
  144. adc_init();
  145. rcin_serial_init();
  146. // power on spektrum port
  147. palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL);
  148. SPEKTRUM_POWER(1);
  149. // we do no allocations after setup completes
  150. reg_status.freemem = hal.util->available_memory();
  151. if (hal.util->was_watchdog_safety_off()) {
  152. hal.rcout->force_safety_off();
  153. reg_status.flag_safety_off = true;
  154. }
  155. }
  156. void AP_IOMCU_FW::update()
  157. {
  158. // we are not running any other threads, so we can use an
  159. // immediate timeout here for lowest latency
  160. eventmask_t mask = chEvtWaitAnyTimeout(~0, TIME_IMMEDIATE);
  161. // we get the timestamp once here, and avoid fetching it
  162. // within the DMA callbacks
  163. last_ms = AP_HAL::millis();
  164. loop_counter++;
  165. if (do_reboot && (last_ms > reboot_time)) {
  166. hal.scheduler->reboot(true);
  167. while (true) {}
  168. }
  169. if ((mask & EVENT_MASK(IOEVENT_PWM)) ||
  170. (last_safety_off != reg_status.flag_safety_off)) {
  171. last_safety_off = reg_status.flag_safety_off;
  172. pwm_out_update();
  173. }
  174. uint32_t now = last_ms;
  175. reg_status.timestamp_ms = last_ms;
  176. // output SBUS if enabled
  177. if ((reg_setup.features & P_SETUP_FEATURES_SBUS1_OUT) &&
  178. reg_status.flag_safety_off &&
  179. now - sbus_last_ms >= sbus_interval_ms) {
  180. // output a new SBUS frame
  181. sbus_last_ms = now;
  182. sbus_out_write(reg_servo.pwm, IOMCU_MAX_CHANNELS);
  183. }
  184. // handle FMU failsafe
  185. if (now - fmu_data_received_time > 200) {
  186. // we are not getting input from the FMU. Fill in failsafe values at 100Hz
  187. if (now - last_failsafe_ms > 10) {
  188. fill_failsafe_pwm();
  189. chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM));
  190. last_failsafe_ms = now;
  191. }
  192. // turn amber on
  193. AMBER_SET(1);
  194. } else {
  195. last_failsafe_ms = now;
  196. // turn amber off
  197. AMBER_SET(0);
  198. }
  199. // update status page at 20Hz
  200. if (now - last_status_ms > 50) {
  201. last_status_ms = now;
  202. page_status_update();
  203. }
  204. // run remaining functions at 1kHz
  205. if (now != last_loop_ms) {
  206. last_loop_ms = now;
  207. heater_update();
  208. rcin_update();
  209. safety_update();
  210. rcout_mode_update();
  211. rcin_serial_update();
  212. hal.rcout->timer_tick();
  213. if (dsm_bind_state) {
  214. dsm_bind_step();
  215. }
  216. }
  217. }
  218. void AP_IOMCU_FW::pwm_out_update()
  219. {
  220. memcpy(reg_servo.pwm, reg_direct_pwm.pwm, sizeof(reg_direct_pwm));
  221. hal.rcout->cork();
  222. for (uint8_t i = 0; i < SERVO_COUNT; i++) {
  223. if (reg_status.flag_safety_off || (reg_setup.ignore_safety & (1U<<i))) {
  224. hal.rcout->write(i, reg_servo.pwm[i]);
  225. } else {
  226. hal.rcout->write(i, 0);
  227. }
  228. }
  229. hal.rcout->push();
  230. }
  231. void AP_IOMCU_FW::heater_update()
  232. {
  233. uint32_t now = last_ms;
  234. if (!has_heater) {
  235. // use blue LED as heartbeat, run it 4x faster when override active
  236. if (now - last_blue_led_ms > (override_active?125:500)) {
  237. BLUE_TOGGLE();
  238. last_blue_led_ms = now;
  239. }
  240. } else if (reg_setup.heater_duty_cycle == 0 || (now - last_heater_ms > 3000UL)) {
  241. // turn off the heater
  242. HEATER_SET(!heater_pwm_polarity);
  243. } else {
  244. // we use a pseudo random sequence to dither the cycling as
  245. // the heater has a significant effect on the internal
  246. // magnetometers. The random generator dithers this so we don't get a 1Hz cycly in the magnetometer.
  247. // The impact on the mags is about 25 mGauss.
  248. bool heater_on = (get_random16() < uint32_t(reg_setup.heater_duty_cycle) * 0xFFFFU / 100U);
  249. HEATER_SET(heater_on? heater_pwm_polarity : !heater_pwm_polarity);
  250. }
  251. }
  252. void AP_IOMCU_FW::rcin_update()
  253. {
  254. ((ChibiOS::RCInput *)hal.rcin)->_timer_tick();
  255. if (hal.rcin->new_input()) {
  256. rc_input.count = hal.rcin->num_channels();
  257. rc_input.flags_rc_ok = true;
  258. for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS; i++) {
  259. rc_input.pwm[i] = hal.rcin->read(i);
  260. }
  261. rc_last_input_ms = last_ms;
  262. rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected();
  263. } else if (last_ms - rc_last_input_ms > 200U) {
  264. rc_input.flags_rc_ok = false;
  265. }
  266. if (update_rcout_freq) {
  267. hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
  268. update_rcout_freq = false;
  269. }
  270. if (update_default_rate) {
  271. hal.rcout->set_default_rate(reg_setup.pwm_defaultrate);
  272. }
  273. bool old_override = override_active;
  274. // check for active override channel
  275. if (mixing.enabled &&
  276. mixing.rc_chan_override > 0 &&
  277. rc_input.flags_rc_ok &&
  278. mixing.rc_chan_override <= IOMCU_MAX_CHANNELS) {
  279. override_active = (rc_input.pwm[mixing.rc_chan_override-1] >= 1750);
  280. } else {
  281. override_active = false;
  282. }
  283. if (old_override != override_active) {
  284. if (override_active) {
  285. fill_failsafe_pwm();
  286. }
  287. chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM));
  288. }
  289. }
  290. void AP_IOMCU_FW::process_io_packet()
  291. {
  292. iomcu.reg_status.total_pkts++;
  293. uint8_t rx_crc = rx_io_packet.crc;
  294. uint8_t calc_crc;
  295. rx_io_packet.crc = 0;
  296. uint8_t pkt_size = rx_io_packet.get_size();
  297. if (rx_io_packet.code == CODE_READ) {
  298. // allow for more bandwidth efficient read packets
  299. calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, 4);
  300. if (calc_crc != rx_crc) {
  301. calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, pkt_size);
  302. }
  303. } else {
  304. calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, pkt_size);
  305. }
  306. if (rx_crc != calc_crc || rx_io_packet.count > PKT_MAX_REGS) {
  307. tx_io_packet.count = 0;
  308. tx_io_packet.code = CODE_CORRUPT;
  309. tx_io_packet.crc = 0;
  310. tx_io_packet.page = 0;
  311. tx_io_packet.offset = 0;
  312. tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
  313. iomcu.reg_status.num_errors++;
  314. iomcu.reg_status.err_crc++;
  315. return;
  316. }
  317. switch (rx_io_packet.code) {
  318. case CODE_READ: {
  319. if (!handle_code_read()) {
  320. tx_io_packet.count = 0;
  321. tx_io_packet.code = CODE_ERROR;
  322. tx_io_packet.crc = 0;
  323. tx_io_packet.page = 0;
  324. tx_io_packet.offset = 0;
  325. tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
  326. iomcu.reg_status.num_errors++;
  327. iomcu.reg_status.err_read++;
  328. }
  329. }
  330. break;
  331. case CODE_WRITE: {
  332. if (!handle_code_write()) {
  333. tx_io_packet.count = 0;
  334. tx_io_packet.code = CODE_ERROR;
  335. tx_io_packet.crc = 0;
  336. tx_io_packet.page = 0;
  337. tx_io_packet.offset = 0;
  338. tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
  339. iomcu.reg_status.num_errors++;
  340. iomcu.reg_status.err_write++;
  341. }
  342. }
  343. break;
  344. default: {
  345. iomcu.reg_status.num_errors++;
  346. iomcu.reg_status.err_bad_opcode++;
  347. }
  348. break;
  349. }
  350. }
  351. /*
  352. update dynamic elements of status page
  353. */
  354. void AP_IOMCU_FW::page_status_update(void)
  355. {
  356. if ((reg_setup.features & P_SETUP_FEATURES_SBUS1_OUT) == 0) {
  357. // we can only get VRSSI when sbus is disabled
  358. reg_status.vrssi = adc_sample_vrssi();
  359. } else {
  360. reg_status.vrssi = 0;
  361. }
  362. reg_status.vservo = adc_sample_vservo();
  363. }
  364. bool AP_IOMCU_FW::handle_code_read()
  365. {
  366. uint16_t *values = nullptr;
  367. #define COPY_PAGE(_page_name) \
  368. do { \
  369. values = (uint16_t *)&_page_name; \
  370. tx_io_packet.count = sizeof(_page_name) / sizeof(uint16_t); \
  371. } while(0);
  372. switch (rx_io_packet.page) {
  373. case PAGE_CONFIG:
  374. COPY_PAGE(config);
  375. break;
  376. case PAGE_SETUP:
  377. COPY_PAGE(reg_setup);
  378. break;
  379. case PAGE_RAW_RCIN:
  380. COPY_PAGE(rc_input);
  381. break;
  382. case PAGE_STATUS:
  383. COPY_PAGE(reg_status);
  384. break;
  385. case PAGE_SERVOS:
  386. COPY_PAGE(reg_servo);
  387. break;
  388. default:
  389. return false;
  390. }
  391. /* if the offset is at or beyond the end of the page, we have no data */
  392. if (rx_io_packet.offset + rx_io_packet.count > tx_io_packet.count) {
  393. return false;
  394. }
  395. /* correct the data pointer and count for the offset */
  396. values += rx_io_packet.offset;
  397. tx_io_packet.page = rx_io_packet.page;
  398. tx_io_packet.offset = rx_io_packet.offset;
  399. tx_io_packet.count -= rx_io_packet.offset;
  400. tx_io_packet.count = MIN(tx_io_packet.count, rx_io_packet.count);
  401. tx_io_packet.count = MIN(tx_io_packet.count, PKT_MAX_REGS);
  402. tx_io_packet.code = CODE_SUCCESS;
  403. memcpy(tx_io_packet.regs, values, sizeof(uint16_t)*tx_io_packet.count);
  404. tx_io_packet.crc = 0;
  405. tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
  406. return true;
  407. }
  408. bool AP_IOMCU_FW::handle_code_write()
  409. {
  410. switch (rx_io_packet.page) {
  411. case PAGE_SETUP:
  412. switch (rx_io_packet.offset) {
  413. case PAGE_REG_SETUP_ARMING:
  414. reg_setup.arming = rx_io_packet.regs[0];
  415. break;
  416. case PAGE_REG_SETUP_FORCE_SAFETY_OFF:
  417. if (rx_io_packet.regs[0] == FORCE_SAFETY_MAGIC) {
  418. hal.rcout->force_safety_off();
  419. reg_status.flag_safety_off = true;
  420. } else {
  421. return false;
  422. }
  423. break;
  424. case PAGE_REG_SETUP_FORCE_SAFETY_ON:
  425. if (rx_io_packet.regs[0] == FORCE_SAFETY_MAGIC) {
  426. hal.rcout->force_safety_on();
  427. reg_status.flag_safety_off = false;
  428. } else {
  429. return false;
  430. }
  431. break;
  432. case PAGE_REG_SETUP_ALTRATE:
  433. reg_setup.pwm_altrate = rx_io_packet.regs[0];
  434. update_rcout_freq = true;
  435. break;
  436. case PAGE_REG_SETUP_PWM_RATE_MASK:
  437. reg_setup.pwm_rates = rx_io_packet.regs[0];
  438. update_rcout_freq = true;
  439. break;
  440. case PAGE_REG_SETUP_DEFAULTRATE:
  441. if (rx_io_packet.regs[0] < 25 && reg_setup.pwm_altclock == 1) {
  442. rx_io_packet.regs[0] = 25;
  443. }
  444. if (rx_io_packet.regs[0] > 400 && reg_setup.pwm_altclock == 1) {
  445. rx_io_packet.regs[0] = 400;
  446. }
  447. reg_setup.pwm_defaultrate = rx_io_packet.regs[0];
  448. update_default_rate = true;
  449. break;
  450. case PAGE_REG_SETUP_SBUS_RATE:
  451. reg_setup.sbus_rate = rx_io_packet.regs[0];
  452. sbus_interval_ms = MAX(1000U / reg_setup.sbus_rate,3);
  453. break;
  454. case PAGE_REG_SETUP_FEATURES:
  455. reg_setup.features = rx_io_packet.regs[0];
  456. /* disable the conflicting options with SBUS 1 */
  457. if (reg_setup.features & (P_SETUP_FEATURES_SBUS1_OUT)) {
  458. reg_setup.features &= ~(P_SETUP_FEATURES_PWM_RSSI |
  459. P_SETUP_FEATURES_ADC_RSSI |
  460. P_SETUP_FEATURES_SBUS2_OUT);
  461. // enable SBUS output at specified rate
  462. sbus_interval_ms = MAX(1000U / reg_setup.sbus_rate,3);
  463. // we need to release the JTAG reset pin to be used as a GPIO, otherwise we can't enable
  464. // or disable SBUS out
  465. AFIO->MAPR = AFIO_MAPR_SWJ_CFG_NOJNTRST;
  466. palClearLine(HAL_GPIO_PIN_SBUS_OUT_EN);
  467. } else {
  468. palSetLine(HAL_GPIO_PIN_SBUS_OUT_EN);
  469. }
  470. break;
  471. case PAGE_REG_SETUP_HEATER_DUTY_CYCLE:
  472. reg_setup.heater_duty_cycle = rx_io_packet.regs[0];
  473. last_heater_ms = last_ms;
  474. break;
  475. case PAGE_REG_SETUP_REBOOT_BL:
  476. if (reg_status.flag_safety_off) {
  477. // don't allow reboot while armed
  478. return false;
  479. }
  480. // check the magic value
  481. if (rx_io_packet.regs[0] != REBOOT_BL_MAGIC) {
  482. return false;
  483. }
  484. schedule_reboot(100);
  485. break;
  486. case PAGE_REG_SETUP_IGNORE_SAFETY:
  487. reg_setup.ignore_safety = rx_io_packet.regs[0];
  488. ((ChibiOS::RCOutput *)hal.rcout)->set_safety_mask(reg_setup.ignore_safety);
  489. break;
  490. case PAGE_REG_SETUP_DSM_BIND:
  491. if (dsm_bind_state == 0) {
  492. dsm_bind_state = 1;
  493. }
  494. break;
  495. default:
  496. break;
  497. }
  498. break;
  499. case PAGE_DIRECT_PWM: {
  500. if (override_active) {
  501. // no input when override is active
  502. break;
  503. }
  504. /* copy channel data */
  505. uint16_t i = 0, offset = rx_io_packet.offset, num_values = rx_io_packet.count;
  506. if (offset + num_values > sizeof(reg_direct_pwm.pwm)/2) {
  507. return false;
  508. }
  509. while ((offset < IOMCU_MAX_CHANNELS) && (num_values > 0)) {
  510. /* XXX range-check value? */
  511. if (rx_io_packet.regs[i] != PWM_IGNORE_THIS_CHANNEL) {
  512. reg_direct_pwm.pwm[offset] = rx_io_packet.regs[i];
  513. }
  514. offset++;
  515. num_values--;
  516. i++;
  517. }
  518. fmu_data_received_time = last_ms;
  519. chEvtSignalI(thread_ctx, EVENT_MASK(IOEVENT_PWM));
  520. break;
  521. }
  522. case PAGE_MIXING: {
  523. uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
  524. if (offset + num_values > sizeof(mixing)/2) {
  525. return false;
  526. }
  527. memcpy(((uint16_t *)&mixing)+offset, &rx_io_packet.regs[0], num_values*2);
  528. break;
  529. }
  530. case PAGE_SAFETY_PWM: {
  531. uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
  532. if (offset + num_values > sizeof(reg_safety_pwm.pwm)/2) {
  533. return false;
  534. }
  535. memcpy((&reg_safety_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2);
  536. break;
  537. }
  538. case PAGE_FAILSAFE_PWM: {
  539. uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count;
  540. if (offset + num_values > sizeof(reg_failsafe_pwm.pwm)/2) {
  541. return false;
  542. }
  543. memcpy((&reg_failsafe_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2);
  544. break;
  545. }
  546. default:
  547. break;
  548. }
  549. tx_io_packet.count = 0;
  550. tx_io_packet.code = CODE_SUCCESS;
  551. tx_io_packet.crc = 0;
  552. tx_io_packet.page = 0;
  553. tx_io_packet.offset = 0;
  554. tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size());
  555. return true;
  556. }
  557. void AP_IOMCU_FW::schedule_reboot(uint32_t time_ms)
  558. {
  559. do_reboot = true;
  560. reboot_time = last_ms + time_ms;
  561. }
  562. void AP_IOMCU_FW::calculate_fw_crc(void)
  563. {
  564. #define APP_SIZE_MAX 0xf000
  565. #define APP_LOAD_ADDRESS 0x08001000
  566. // compute CRC of the current firmware
  567. uint32_t sum = 0;
  568. for (unsigned p = 0; p < APP_SIZE_MAX; p += 4) {
  569. uint32_t bytes = *(uint32_t *)(p + APP_LOAD_ADDRESS);
  570. sum = crc_crc32(sum, (const uint8_t *)&bytes, sizeof(bytes));
  571. }
  572. reg_setup.crc[0] = sum & 0xFFFF;
  573. reg_setup.crc[1] = sum >> 16;
  574. }
  575. /*
  576. update safety state
  577. */
  578. void AP_IOMCU_FW::safety_update(void)
  579. {
  580. uint32_t now = last_ms;
  581. if (now - safety_update_ms < 100) {
  582. // update safety at 10Hz
  583. return;
  584. }
  585. safety_update_ms = now;
  586. bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_INPUT);
  587. if (safety_pressed) {
  588. if (reg_status.flag_safety_off && (reg_setup.arming & P_SETUP_ARMING_SAFETY_DISABLE_ON)) {
  589. safety_pressed = false;
  590. } else if ((!reg_status.flag_safety_off) && (reg_setup.arming & P_SETUP_ARMING_SAFETY_DISABLE_OFF)) {
  591. safety_pressed = false;
  592. }
  593. }
  594. if (safety_pressed) {
  595. safety_button_counter++;
  596. } else {
  597. safety_button_counter = 0;
  598. }
  599. if (safety_button_counter == 10) {
  600. // safety has been pressed for 1 second, change state
  601. reg_status.flag_safety_off = !reg_status.flag_safety_off;
  602. if (reg_status.flag_safety_off) {
  603. hal.rcout->force_safety_off();
  604. } else {
  605. hal.rcout->force_safety_on();
  606. }
  607. }
  608. #if IOMCU_ENABLE_WATCHDOG_TEST
  609. if (safety_button_counter == 50) {
  610. // deliberate lockup of IOMCU on 5s button press, for testing
  611. // watchdog
  612. while (true) {
  613. hal.scheduler->delay(50);
  614. palToggleLine(HAL_GPIO_PIN_SAFETY_LED);
  615. if (palReadLine(HAL_GPIO_PIN_SAFETY_INPUT)) {
  616. // only trigger watchdog on button release, so we
  617. // don't end up stuck in the bootloader
  618. stm32_watchdog_pat();
  619. }
  620. }
  621. }
  622. #endif
  623. led_counter = (led_counter+1) % 16;
  624. const uint16_t led_pattern = reg_status.flag_safety_off?0xFFFF:0x5500;
  625. palWriteLine(HAL_GPIO_PIN_SAFETY_LED, (led_pattern & (1U << led_counter))?0:1);
  626. }
  627. /*
  628. update hal.rcout mode if needed
  629. */
  630. void AP_IOMCU_FW::rcout_mode_update(void)
  631. {
  632. bool use_oneshot = (reg_setup.features & P_SETUP_FEATURES_ONESHOT) != 0;
  633. if (use_oneshot && !oneshot_enabled) {
  634. oneshot_enabled = true;
  635. hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
  636. }
  637. bool use_brushed = (reg_setup.features & P_SETUP_FEATURES_BRUSHED) != 0;
  638. if (use_brushed && !brushed_enabled) {
  639. brushed_enabled = true;
  640. if (reg_setup.pwm_rates == 0) {
  641. // default to 2kHz for all channels for brushed output
  642. reg_setup.pwm_rates = 0xFF;
  643. reg_setup.pwm_altrate = 2000;
  644. hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
  645. }
  646. hal.rcout->set_esc_scaling(1000, 2000);
  647. hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
  648. hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate);
  649. }
  650. }
  651. /*
  652. fill in failsafe PWM values
  653. */
  654. void AP_IOMCU_FW::fill_failsafe_pwm(void)
  655. {
  656. for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
  657. if (reg_status.flag_safety_off) {
  658. reg_direct_pwm.pwm[i] = reg_failsafe_pwm.pwm[i];
  659. } else {
  660. reg_direct_pwm.pwm[i] = reg_safety_pwm.pwm[i];
  661. }
  662. }
  663. if (mixing.enabled) {
  664. run_mixer();
  665. }
  666. }
  667. AP_HAL_MAIN();