AP_IOMCU.cpp 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002
  1. /*
  2. implement protocol for controlling an IO microcontroller
  3. For bootstrapping this will initially implement the px4io protocol,
  4. but will later move to an ArduPilot specific protocol
  5. */
  6. #include "AP_IOMCU.h"
  7. #if HAL_WITH_IO_MCU
  8. #include <AP_Math/AP_Math.h>
  9. #include <AP_Math/crc.h>
  10. #include <AP_BoardConfig/AP_BoardConfig.h>
  11. #include <AP_ROMFS/AP_ROMFS.h>
  12. #include <AP_Math/crc.h>
  13. #include <SRV_Channel/SRV_Channel.h>
  14. #include <RC_Channel/RC_Channel.h>
  15. #include <AP_RCProtocol/AP_RCProtocol.h>
  16. #include <AP_InternalError/AP_InternalError.h>
  17. #include <AP_Logger/AP_Logger.h>
  18. extern const AP_HAL::HAL &hal;
  19. // pending IO events to send, used as an event mask
  20. enum ioevents {
  21. IOEVENT_INIT=1,
  22. IOEVENT_SEND_PWM_OUT,
  23. IOEVENT_FORCE_SAFETY_OFF,
  24. IOEVENT_FORCE_SAFETY_ON,
  25. IOEVENT_SET_ONESHOT_ON,
  26. IOEVENT_SET_BRUSHED_ON,
  27. IOEVENT_SET_RATES,
  28. IOEVENT_ENABLE_SBUS,
  29. IOEVENT_SET_HEATER_TARGET,
  30. IOEVENT_SET_DEFAULT_RATE,
  31. IOEVENT_SET_SAFETY_MASK,
  32. IOEVENT_MIXING
  33. };
  34. // max number of consecutve protocol failures we accept before raising
  35. // an error
  36. #define IOMCU_MAX_REPEATED_FAILURES 20
  37. AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) :
  38. uart(_uart)
  39. {}
  40. #define IOMCU_DEBUG_ENABLE 0
  41. #if IOMCU_DEBUG_ENABLE
  42. #define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  43. #else
  44. #define debug(fmt, args ...)
  45. #endif
  46. /*
  47. initialise library, starting thread
  48. */
  49. void AP_IOMCU::init(void)
  50. {
  51. // uart runs at 1.5MBit
  52. uart.begin(1500*1000, 256, 256);
  53. uart.set_blocking_writes(true);
  54. uart.set_unbuffered_writes(true);
  55. AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
  56. if ((!boardconfig || boardconfig->io_enabled() == 1) && !hal.util->was_watchdog_reset()) {
  57. check_crc();
  58. } else {
  59. crc_is_ok = true;
  60. }
  61. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU",
  62. 1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
  63. AP_HAL::panic("Unable to allocate IOMCU thread");
  64. }
  65. initialised = true;
  66. }
  67. /*
  68. handle event failure
  69. */
  70. void AP_IOMCU::event_failed(uint8_t event)
  71. {
  72. // wait 0.5ms then retry
  73. hal.scheduler->delay_microseconds(500);
  74. trigger_event(event);
  75. }
  76. /*
  77. main IO thread loop
  78. */
  79. void AP_IOMCU::thread_main(void)
  80. {
  81. thread_ctx = chThdGetSelfX();
  82. chEvtSignal(thread_ctx, initial_event_mask);
  83. uart.begin(1500*1000, 256, 256);
  84. uart.set_blocking_writes(true);
  85. uart.set_unbuffered_writes(true);
  86. trigger_event(IOEVENT_INIT);
  87. while (!do_shutdown) {
  88. eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10));
  89. // check for pending IO events
  90. if (mask & EVENT_MASK(IOEVENT_SEND_PWM_OUT)) {
  91. send_servo_out();
  92. }
  93. if (mask & EVENT_MASK(IOEVENT_INIT)) {
  94. // get protocol version
  95. if (!read_registers(PAGE_CONFIG, 0, sizeof(config)/2, (uint16_t *)&config)) {
  96. event_failed(IOEVENT_INIT);
  97. continue;
  98. }
  99. is_chibios_backend = (config.protocol_version == IOMCU_PROTOCOL_VERSION &&
  100. config.protocol_version2 == IOMCU_PROTOCOL_VERSION2);
  101. // set IO_ARM_OK and FMU_ARMED
  102. if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, 0,
  103. P_SETUP_ARMING_IO_ARM_OK |
  104. P_SETUP_ARMING_FMU_ARMED |
  105. P_SETUP_ARMING_RC_HANDLING_DISABLED)) {
  106. event_failed(IOEVENT_INIT);
  107. continue;
  108. }
  109. }
  110. if (mask & EVENT_MASK(IOEVENT_MIXING)) {
  111. if (!write_registers(PAGE_MIXING, 0, sizeof(mixing)/2, (const uint16_t *)&mixing)) {
  112. event_failed(IOEVENT_MIXING);
  113. continue;
  114. }
  115. }
  116. if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_OFF)) {
  117. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_OFF, FORCE_SAFETY_MAGIC)) {
  118. event_failed(IOEVENT_FORCE_SAFETY_OFF);
  119. continue;
  120. }
  121. }
  122. if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_ON)) {
  123. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_ON, FORCE_SAFETY_MAGIC)) {
  124. event_failed(IOEVENT_FORCE_SAFETY_ON);
  125. continue;
  126. }
  127. }
  128. if (mask & EVENT_MASK(IOEVENT_SET_RATES)) {
  129. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) ||
  130. !write_register(PAGE_SETUP, PAGE_REG_SETUP_PWM_RATE_MASK, rate.chmask)) {
  131. event_failed(IOEVENT_SET_RATES);
  132. continue;
  133. }
  134. }
  135. if (mask & EVENT_MASK(IOEVENT_ENABLE_SBUS)) {
  136. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_SBUS_RATE, rate.sbus_rate_hz) ||
  137. !modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0,
  138. P_SETUP_FEATURES_SBUS1_OUT)) {
  139. event_failed(IOEVENT_ENABLE_SBUS);
  140. continue;
  141. }
  142. }
  143. if (mask & EVENT_MASK(IOEVENT_SET_HEATER_TARGET)) {
  144. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_HEATER_DUTY_CYCLE, heater_duty_cycle)) {
  145. event_failed(IOEVENT_SET_HEATER_TARGET);
  146. continue;
  147. }
  148. }
  149. if (mask & EVENT_MASK(IOEVENT_SET_DEFAULT_RATE)) {
  150. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_DEFAULTRATE, rate.default_freq)) {
  151. event_failed(IOEVENT_SET_DEFAULT_RATE);
  152. continue;
  153. }
  154. }
  155. if (mask & EVENT_MASK(IOEVENT_SET_ONESHOT_ON)) {
  156. if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_ONESHOT)) {
  157. event_failed(IOEVENT_SET_ONESHOT_ON);
  158. continue;
  159. }
  160. }
  161. if (mask & EVENT_MASK(IOEVENT_SET_BRUSHED_ON)) {
  162. if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_BRUSHED)) {
  163. event_failed(IOEVENT_SET_BRUSHED_ON);
  164. continue;
  165. }
  166. }
  167. if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) {
  168. if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) {
  169. event_failed(IOEVENT_SET_SAFETY_MASK);
  170. continue;
  171. }
  172. }
  173. // check for regular timed events
  174. uint32_t now = AP_HAL::millis();
  175. if (now - last_rc_read_ms > 20) {
  176. // read RC input at 50Hz
  177. read_rc_input();
  178. last_rc_read_ms = AP_HAL::millis();
  179. }
  180. if (now - last_status_read_ms > 50) {
  181. // read status at 20Hz
  182. read_status();
  183. last_status_read_ms = AP_HAL::millis();
  184. }
  185. if (now - last_servo_read_ms > 50) {
  186. // read servo out at 20Hz
  187. read_servo();
  188. last_servo_read_ms = AP_HAL::millis();
  189. }
  190. if (now - last_safety_option_check_ms > 1000) {
  191. update_safety_options();
  192. last_safety_option_check_ms = now;
  193. }
  194. // update safety pwm
  195. if (pwm_out.safety_pwm_set != pwm_out.safety_pwm_sent) {
  196. uint8_t set = pwm_out.safety_pwm_set;
  197. if (write_registers(PAGE_SAFETY_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.safety_pwm)) {
  198. pwm_out.safety_pwm_sent = set;
  199. }
  200. }
  201. // update failsafe pwm
  202. if (pwm_out.failsafe_pwm_set != pwm_out.failsafe_pwm_sent) {
  203. uint8_t set = pwm_out.failsafe_pwm_set;
  204. if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.failsafe_pwm)) {
  205. pwm_out.failsafe_pwm_sent = set;
  206. }
  207. }
  208. }
  209. done_shutdown = true;
  210. }
  211. /*
  212. send servo output data
  213. */
  214. void AP_IOMCU::send_servo_out()
  215. {
  216. #if 0
  217. // simple method to test IO failsafe
  218. if (AP_HAL::millis() > 30000) {
  219. return;
  220. }
  221. #endif
  222. if (pwm_out.num_channels > 0) {
  223. uint8_t n = pwm_out.num_channels;
  224. if (rate.sbus_rate_hz == 0) {
  225. n = MIN(n, 8);
  226. } else {
  227. n = MIN(n, IOMCU_MAX_CHANNELS);
  228. }
  229. uint32_t now = AP_HAL::micros();
  230. if (now - last_servo_out_us >= 2000) {
  231. // don't send data at more than 500Hz
  232. if (write_registers(PAGE_DIRECT_PWM, 0, n, pwm_out.pwm)) {
  233. last_servo_out_us = now;
  234. }
  235. }
  236. }
  237. }
  238. /*
  239. read RC input
  240. */
  241. void AP_IOMCU::read_rc_input()
  242. {
  243. uint16_t *r = (uint16_t *)&rc_input;
  244. if (!read_registers(PAGE_RAW_RCIN, 0, sizeof(rc_input)/2, r)) {
  245. return;
  246. }
  247. if (rc_input.flags_rc_ok && !rc_input.flags_failsafe) {
  248. rc_last_input_ms = AP_HAL::millis();
  249. }
  250. }
  251. /*
  252. read status registers
  253. */
  254. void AP_IOMCU::read_status()
  255. {
  256. uint16_t *r = (uint16_t *)&reg_status;
  257. if (!read_registers(PAGE_STATUS, 0, sizeof(reg_status)/2, r)) {
  258. return;
  259. }
  260. check_iomcu_reset();
  261. if (reg_status.flag_safety_off == 0) {
  262. // if the IOMCU is indicating that safety is on, then force a
  263. // re-check of the safety options. This copes with a IOMCU reset
  264. last_safety_options = 0xFFFF;
  265. // also check if the safety should be definately off.
  266. AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
  267. if (!boardconfig) {
  268. return;
  269. }
  270. uint16_t options = boardconfig->get_safety_button_options();
  271. if (safety_forced_off && (options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON) == 0) {
  272. // the safety has been forced off, and the user has asked
  273. // that the button can never be used, so there should be
  274. // no way for the safety to be on except a IOMCU
  275. // reboot. Force safety off again
  276. force_safety_off();
  277. }
  278. }
  279. uint32_t now = AP_HAL::millis();
  280. if (now - last_log_ms >= 1000U) {
  281. last_log_ms = now;
  282. AP::logger().Write("IOMC", "TimeUS,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHIIIII",
  283. AP_HAL::micros64(),
  284. reg_status.freemem,
  285. reg_status.timestamp_ms,
  286. reg_status.total_pkts,
  287. total_errors,
  288. reg_status.num_errors,
  289. num_delayed);
  290. #if IOMCU_DEBUG_ENABLE
  291. static uint32_t last_io_print;
  292. if (now - last_io_print >= 5000) {
  293. last_io_print = now;
  294. debug("t=%u num=%u terr=%u nerr=%u crc=%u opcode=%u rd=%u wr=%u ur=%u ndel=%u\n",
  295. now,
  296. reg_status.total_pkts,
  297. total_errors,
  298. reg_status.num_errors,
  299. reg_status.err_crc,
  300. reg_status.err_bad_opcode,
  301. reg_status.err_read,
  302. reg_status.err_write,
  303. reg_status.err_uart,
  304. num_delayed);
  305. }
  306. #endif // IOMCU_DEBUG_ENABLE
  307. }
  308. }
  309. /*
  310. read servo output values
  311. */
  312. void AP_IOMCU::read_servo()
  313. {
  314. if (pwm_out.num_channels > 0) {
  315. read_registers(PAGE_SERVOS, 0, pwm_out.num_channels, pwm_in.pwm);
  316. }
  317. }
  318. /*
  319. discard any pending input
  320. */
  321. void AP_IOMCU::discard_input(void)
  322. {
  323. uint32_t n = uart.available();
  324. while (n--) {
  325. uart.read();
  326. }
  327. }
  328. /*
  329. write a packet, retrying as needed
  330. */
  331. size_t AP_IOMCU::write_wait(const uint8_t *pkt, uint8_t len)
  332. {
  333. uint8_t wait_count = 5;
  334. size_t ret;
  335. do {
  336. ret = uart.write(pkt, len);
  337. if (ret == 0) {
  338. hal.scheduler->delay_microseconds(100);
  339. num_delayed++;
  340. }
  341. } while (ret == 0 && wait_count--);
  342. return ret;
  343. }
  344. /*
  345. read count 16 bit registers
  346. */
  347. bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint16_t *regs)
  348. {
  349. while (count > PKT_MAX_REGS) {
  350. if (!read_registers(page, offset, PKT_MAX_REGS, regs)) {
  351. return false;
  352. }
  353. offset += PKT_MAX_REGS;
  354. count -= PKT_MAX_REGS;
  355. regs += PKT_MAX_REGS;
  356. }
  357. IOPacket pkt;
  358. discard_input();
  359. memset(&pkt.regs[0], 0, count*2);
  360. pkt.code = CODE_READ;
  361. pkt.count = count;
  362. pkt.page = page;
  363. pkt.offset = offset;
  364. pkt.crc = 0;
  365. uint8_t pkt_size = pkt.get_size();
  366. if (is_chibios_backend) {
  367. /*
  368. the original read protocol is a bit strange, as it
  369. unnecessarily sends the same size packet that it expects to
  370. receive. This means reading a large number of registers
  371. wastes a lot of serial bandwidth. We avoid this overhead
  372. when we know we are talking to a ChibiOS backend
  373. */
  374. pkt_size = 4;
  375. }
  376. pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size);
  377. size_t ret = write_wait((uint8_t *)&pkt, pkt_size);
  378. if (ret != pkt_size) {
  379. debug("write failed1 %u %u %u\n", unsigned(pkt_size), page, offset);
  380. protocol_fail_count++;
  381. return false;
  382. }
  383. // wait for the expected number of reply bytes or timeout
  384. if (!uart.wait_timeout(count*2+4, 10)) {
  385. debug("t=%u timeout read page=%u offset=%u count=%u\n",
  386. AP_HAL::millis(), page, offset, count);
  387. return false;
  388. }
  389. uint8_t *b = (uint8_t *)&pkt;
  390. uint8_t n = uart.available();
  391. if (n < offsetof(struct IOPacket, regs)) {
  392. debug("t=%u small pkt %u\n", AP_HAL::millis(), n);
  393. protocol_fail_count++;
  394. return false;
  395. }
  396. if (pkt.get_size() != n) {
  397. debug("t=%u bad len %u %u\n", AP_HAL::millis(), n, pkt.get_size());
  398. protocol_fail_count++;
  399. return false;
  400. }
  401. for (uint8_t i=0; i<n; i++) {
  402. if (i < sizeof(pkt)) {
  403. b[i] = uart.read();
  404. }
  405. }
  406. uint8_t got_crc = pkt.crc;
  407. pkt.crc = 0;
  408. uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
  409. if (got_crc != expected_crc) {
  410. debug("t=%u bad crc %02x should be %02x n=%u %u/%u/%u\n",
  411. AP_HAL::millis(), got_crc, expected_crc,
  412. n, page, offset, count);
  413. protocol_fail_count++;
  414. return false;
  415. }
  416. if (pkt.code != CODE_SUCCESS) {
  417. debug("bad code %02x read %u/%u/%u\n", pkt.code, page, offset, count);
  418. protocol_fail_count++;
  419. return false;
  420. }
  421. if (pkt.count < count) {
  422. debug("bad count %u read %u/%u/%u n=%u\n", pkt.count, page, offset, count, n);
  423. protocol_fail_count++;
  424. return false;
  425. }
  426. memcpy(regs, pkt.regs, count*2);
  427. if (protocol_fail_count > IOMCU_MAX_REPEATED_FAILURES) {
  428. handle_repeated_failures();
  429. }
  430. total_errors += protocol_fail_count;
  431. protocol_fail_count = 0;
  432. protocol_count++;
  433. return true;
  434. }
  435. /*
  436. write count 16 bit registers
  437. */
  438. bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs)
  439. {
  440. while (count > PKT_MAX_REGS) {
  441. if (!write_registers(page, offset, PKT_MAX_REGS, regs)) {
  442. return false;
  443. }
  444. offset += PKT_MAX_REGS;
  445. count -= PKT_MAX_REGS;
  446. regs += PKT_MAX_REGS;
  447. }
  448. IOPacket pkt;
  449. discard_input();
  450. memset(&pkt.regs[0], 0, count*2);
  451. pkt.code = CODE_WRITE;
  452. pkt.count = count;
  453. pkt.page = page;
  454. pkt.offset = offset;
  455. pkt.crc = 0;
  456. memcpy(pkt.regs, regs, 2*count);
  457. pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
  458. const uint8_t pkt_size = pkt.get_size();
  459. size_t ret = write_wait((uint8_t *)&pkt, pkt_size);
  460. if (ret != pkt_size) {
  461. debug("write failed2 %u %u %u %u\n", pkt_size, page, offset, ret);
  462. protocol_fail_count++;
  463. return false;
  464. }
  465. // wait for the expected number of reply bytes or timeout
  466. if (!uart.wait_timeout(4, 10)) {
  467. debug("no reply for %u/%u/%u\n", page, offset, count);
  468. protocol_fail_count++;
  469. return false;
  470. }
  471. uint8_t *b = (uint8_t *)&pkt;
  472. uint8_t n = uart.available();
  473. for (uint8_t i=0; i<n; i++) {
  474. if (i < sizeof(pkt)) {
  475. b[i] = uart.read();
  476. }
  477. }
  478. if (pkt.code != CODE_SUCCESS) {
  479. debug("bad code %02x write %u/%u/%u %02x/%02x n=%u\n",
  480. pkt.code, page, offset, count,
  481. pkt.page, pkt.offset, n);
  482. protocol_fail_count++;
  483. return false;
  484. }
  485. uint8_t got_crc = pkt.crc;
  486. pkt.crc = 0;
  487. uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
  488. if (got_crc != expected_crc) {
  489. debug("bad crc %02x should be %02x\n", got_crc, expected_crc);
  490. protocol_fail_count++;
  491. return false;
  492. }
  493. if (protocol_fail_count > IOMCU_MAX_REPEATED_FAILURES) {
  494. handle_repeated_failures();
  495. }
  496. total_errors += protocol_fail_count;
  497. protocol_fail_count = 0;
  498. protocol_count++;
  499. return true;
  500. }
  501. // modify a single register
  502. bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits)
  503. {
  504. uint16_t v = 0;
  505. if (!read_registers(page, offset, 1, &v)) {
  506. return false;
  507. }
  508. uint16_t v2 = (v & ~clearbits) | setbits;
  509. if (v2 == v) {
  510. return true;
  511. }
  512. return write_registers(page, offset, 1, &v2);
  513. }
  514. void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm)
  515. {
  516. if (chan >= IOMCU_MAX_CHANNELS) {
  517. return;
  518. }
  519. if (chan >= pwm_out.num_channels) {
  520. pwm_out.num_channels = chan+1;
  521. }
  522. pwm_out.pwm[chan] = pwm;
  523. if (!corked) {
  524. push();
  525. }
  526. }
  527. // trigger an ioevent
  528. void AP_IOMCU::trigger_event(uint8_t event)
  529. {
  530. if (thread_ctx != nullptr) {
  531. chEvtSignal(thread_ctx, EVENT_MASK(event));
  532. } else {
  533. // thread isn't started yet, trigger this event once it is started
  534. initial_event_mask |= EVENT_MASK(event);
  535. }
  536. }
  537. // get state of safety switch
  538. AP_HAL::Util::safety_state AP_IOMCU::get_safety_switch_state(void) const
  539. {
  540. return reg_status.flag_safety_off?AP_HAL::Util::SAFETY_ARMED:AP_HAL::Util::SAFETY_DISARMED;
  541. }
  542. // force safety on
  543. bool AP_IOMCU::force_safety_on(void)
  544. {
  545. trigger_event(IOEVENT_FORCE_SAFETY_ON);
  546. safety_forced_off = false;
  547. return true;
  548. }
  549. // force safety off
  550. void AP_IOMCU::force_safety_off(void)
  551. {
  552. trigger_event(IOEVENT_FORCE_SAFETY_OFF);
  553. safety_forced_off = true;
  554. }
  555. // read from one channel
  556. uint16_t AP_IOMCU::read_channel(uint8_t chan)
  557. {
  558. return pwm_in.pwm[chan];
  559. }
  560. // cork output
  561. void AP_IOMCU::cork(void)
  562. {
  563. corked = true;
  564. }
  565. // push output
  566. void AP_IOMCU::push(void)
  567. {
  568. trigger_event(IOEVENT_SEND_PWM_OUT);
  569. corked = false;
  570. }
  571. // set output frequency
  572. void AP_IOMCU::set_freq(uint16_t chmask, uint16_t freq)
  573. {
  574. // ensure mask is legal for the timer layout
  575. for (uint8_t i=0; i<ARRAY_SIZE(ch_masks); i++) {
  576. if (chmask & ch_masks[i]) {
  577. chmask |= ch_masks[i];
  578. }
  579. }
  580. rate.freq = freq;
  581. rate.chmask |= chmask;
  582. trigger_event(IOEVENT_SET_RATES);
  583. }
  584. // get output frequency
  585. uint16_t AP_IOMCU::get_freq(uint16_t chan)
  586. {
  587. if ((1U<<chan) & rate.chmask) {
  588. return rate.freq;
  589. }
  590. return rate.default_freq;
  591. }
  592. // enable SBUS out
  593. bool AP_IOMCU::enable_sbus_out(uint16_t rate_hz)
  594. {
  595. rate.sbus_rate_hz = rate_hz;
  596. trigger_event(IOEVENT_ENABLE_SBUS);
  597. return true;
  598. }
  599. /*
  600. check for new RC input
  601. */
  602. bool AP_IOMCU::check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_chan)
  603. {
  604. if (last_frame_us != uint32_t(rc_last_input_ms * 1000U)) {
  605. num_channels = MIN(MIN(rc_input.count, IOMCU_MAX_CHANNELS), max_chan);
  606. memcpy(channels, rc_input.pwm, num_channels*2);
  607. last_frame_us = uint32_t(rc_last_input_ms * 1000U);
  608. return true;
  609. }
  610. return false;
  611. }
  612. // set IMU heater target
  613. void AP_IOMCU::set_heater_duty_cycle(uint8_t duty_cycle)
  614. {
  615. heater_duty_cycle = duty_cycle;
  616. trigger_event(IOEVENT_SET_HEATER_TARGET);
  617. }
  618. // set default output rate
  619. void AP_IOMCU::set_default_rate(uint16_t rate_hz)
  620. {
  621. if (rate.default_freq != rate_hz) {
  622. rate.default_freq = rate_hz;
  623. trigger_event(IOEVENT_SET_DEFAULT_RATE);
  624. }
  625. }
  626. // setup for oneshot mode
  627. void AP_IOMCU::set_oneshot_mode(void)
  628. {
  629. trigger_event(IOEVENT_SET_ONESHOT_ON);
  630. }
  631. // setup for brushed mode
  632. void AP_IOMCU::set_brushed_mode(void)
  633. {
  634. trigger_event(IOEVENT_SET_BRUSHED_ON);
  635. }
  636. // handling of BRD_SAFETYOPTION parameter
  637. void AP_IOMCU::update_safety_options(void)
  638. {
  639. AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
  640. if (!boardconfig) {
  641. return;
  642. }
  643. uint16_t desired_options = 0;
  644. uint16_t options = boardconfig->get_safety_button_options();
  645. if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {
  646. desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_OFF;
  647. }
  648. if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {
  649. desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_ON;
  650. }
  651. if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) && hal.util->get_soft_armed()) {
  652. desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
  653. }
  654. if (last_safety_options != desired_options) {
  655. uint16_t mask = (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
  656. uint32_t bits_to_set = desired_options & mask;
  657. uint32_t bits_to_clear = (~desired_options) & mask;
  658. if (modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, bits_to_clear, bits_to_set)) {
  659. last_safety_options = desired_options;
  660. }
  661. }
  662. }
  663. /*
  664. check ROMFS firmware against CRC on IOMCU, and if incorrect then upload new firmware
  665. */
  666. bool AP_IOMCU::check_crc(void)
  667. {
  668. // flash size minus 4k bootloader
  669. const uint32_t flash_size = 0x10000 - 0x1000;
  670. fw = AP_ROMFS::find_decompress(fw_name, fw_size);
  671. if (!fw) {
  672. hal.console->printf("failed to find %s\n", fw_name);
  673. return false;
  674. }
  675. uint32_t crc = crc_crc32(0, fw, fw_size);
  676. // pad CRC to max size
  677. for (uint32_t i=0; i<flash_size-fw_size; i++) {
  678. uint8_t b = 0xff;
  679. crc = crc_crc32(crc, &b, 1);
  680. }
  681. uint32_t io_crc = 0;
  682. uint8_t tries = 32;
  683. while (tries--) {
  684. if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc)) {
  685. break;
  686. }
  687. }
  688. if (io_crc == crc) {
  689. hal.console->printf("IOMCU: CRC ok\n");
  690. crc_is_ok = true;
  691. free(fw);
  692. fw = nullptr;
  693. return true;
  694. } else {
  695. hal.console->printf("IOMCU: CRC mismatch expected: 0x%X got: 0x%X\n", (unsigned)crc, (unsigned)io_crc);
  696. }
  697. const uint16_t magic = REBOOT_BL_MAGIC;
  698. write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
  699. if (!upload_fw()) {
  700. free(fw);
  701. fw = nullptr;
  702. AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
  703. }
  704. free(fw);
  705. fw = nullptr;
  706. return false;
  707. }
  708. /*
  709. set the pwm to use when safety is on
  710. */
  711. void AP_IOMCU::set_safety_pwm(uint16_t chmask, uint16_t period_us)
  712. {
  713. bool changed = false;
  714. for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
  715. if (chmask & (1U<<i)) {
  716. if (pwm_out.safety_pwm[i] != period_us) {
  717. pwm_out.safety_pwm[i] = period_us;
  718. changed = true;
  719. }
  720. }
  721. }
  722. if (changed) {
  723. pwm_out.safety_pwm_set++;
  724. }
  725. }
  726. /*
  727. set the pwm to use when in FMU failsafe
  728. */
  729. void AP_IOMCU::set_failsafe_pwm(uint16_t chmask, uint16_t period_us)
  730. {
  731. bool changed = false;
  732. for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
  733. if (chmask & (1U<<i)) {
  734. if (pwm_out.failsafe_pwm[i] != period_us) {
  735. pwm_out.failsafe_pwm[i] = period_us;
  736. changed = true;
  737. }
  738. }
  739. }
  740. if (changed) {
  741. pwm_out.failsafe_pwm_set++;
  742. }
  743. }
  744. // set mask of channels that ignore safety state
  745. void AP_IOMCU::set_safety_mask(uint16_t chmask)
  746. {
  747. if (pwm_out.safety_mask != chmask) {
  748. pwm_out.safety_mask = chmask;
  749. trigger_event(IOEVENT_SET_SAFETY_MASK);
  750. }
  751. }
  752. /*
  753. check that IO is healthy. This should be used in arming checks
  754. */
  755. bool AP_IOMCU::healthy(void)
  756. {
  757. return crc_is_ok && protocol_fail_count == 0 && !detected_io_reset;
  758. }
  759. /*
  760. shutdown protocol, ready for reboot
  761. */
  762. void AP_IOMCU::shutdown(void)
  763. {
  764. do_shutdown = true;
  765. while (!done_shutdown) {
  766. hal.scheduler->delay(1);
  767. }
  768. }
  769. /*
  770. request bind on a DSM radio
  771. */
  772. void AP_IOMCU::bind_dsm(uint8_t mode)
  773. {
  774. if (!is_chibios_backend || hal.util->get_soft_armed()) {
  775. // only with ChibiOS IO firmware, and disarmed
  776. return;
  777. }
  778. uint16_t reg = mode;
  779. write_registers(PAGE_SETUP, PAGE_REG_SETUP_DSM_BIND, 1, &reg);
  780. }
  781. /*
  782. setup for mixing. This allows fixed wing aircraft to fly in manual
  783. mode if the FMU dies
  784. */
  785. bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
  786. float mixing_gain, uint16_t manual_rc_mask)
  787. {
  788. if (!is_chibios_backend) {
  789. return false;
  790. }
  791. bool changed = false;
  792. #define MIX_UPDATE(a,b) do { if ((a) != (b)) { a = b; changed = true; }} while (0)
  793. // update mixing structure, checking for changes
  794. for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
  795. const SRV_Channel *c = SRV_Channels::srv_channel(i);
  796. if (!c) {
  797. continue;
  798. }
  799. MIX_UPDATE(mixing.servo_trim[i], c->get_trim());
  800. MIX_UPDATE(mixing.servo_min[i], c->get_output_min());
  801. MIX_UPDATE(mixing.servo_max[i], c->get_output_max());
  802. MIX_UPDATE(mixing.servo_function[i], c->get_function());
  803. MIX_UPDATE(mixing.servo_reversed[i], c->get_reversed());
  804. }
  805. // update RCMap
  806. MIX_UPDATE(mixing.rc_channel[0], rcmap->roll());
  807. MIX_UPDATE(mixing.rc_channel[1], rcmap->pitch());
  808. MIX_UPDATE(mixing.rc_channel[2], rcmap->throttle());
  809. MIX_UPDATE(mixing.rc_channel[3], rcmap->yaw());
  810. for (uint8_t i=0; i<4; i++) {
  811. const RC_Channel *c = RC_Channels::rc_channel(mixing.rc_channel[i]-1);
  812. if (!c) {
  813. continue;
  814. }
  815. MIX_UPDATE(mixing.rc_min[i], c->get_radio_min());
  816. MIX_UPDATE(mixing.rc_max[i], c->get_radio_max());
  817. MIX_UPDATE(mixing.rc_trim[i], c->get_radio_trim());
  818. MIX_UPDATE(mixing.rc_reversed[i], c->get_reverse());
  819. // cope with reversible throttle
  820. if (i == 2 && c->get_type() == RC_Channel::RC_CHANNEL_TYPE_ANGLE) {
  821. MIX_UPDATE(mixing.throttle_is_angle, 1);
  822. } else {
  823. MIX_UPDATE(mixing.throttle_is_angle, 0);
  824. }
  825. }
  826. MIX_UPDATE(mixing.rc_chan_override, override_chan);
  827. MIX_UPDATE(mixing.mixing_gain, (uint16_t)(mixing_gain*1000));
  828. MIX_UPDATE(mixing.manual_rc_mask, manual_rc_mask);
  829. // and enable
  830. MIX_UPDATE(mixing.enabled, 1);
  831. if (changed) {
  832. trigger_event(IOEVENT_MIXING);
  833. }
  834. return true;
  835. }
  836. /*
  837. return the RC protocol name
  838. */
  839. const char *AP_IOMCU::get_rc_protocol(void)
  840. {
  841. if (!is_chibios_backend) {
  842. return nullptr;
  843. }
  844. return AP_RCProtocol::protocol_name_from_protocol((AP_RCProtocol::rcprotocol_t)rc_input.rc_protocol);
  845. }
  846. /*
  847. we have had a series of repeated protocol failures to the
  848. IOMCU. This may indicate that the IOMCU has been reset (possibly due
  849. to a watchdog).
  850. */
  851. void AP_IOMCU::handle_repeated_failures(void)
  852. {
  853. if (protocol_count < 100) {
  854. // we're just starting up, ignore initial failures caused by
  855. // initial sync with IOMCU
  856. return;
  857. }
  858. AP::internalerror().error(AP_InternalError::error_t::iomcu_fail);
  859. }
  860. /*
  861. check for IOMCU reset (possibly due to a watchdog).
  862. */
  863. void AP_IOMCU::check_iomcu_reset(void)
  864. {
  865. if (last_iocmu_timestamp_ms == 0) {
  866. // initialisation
  867. last_iocmu_timestamp_ms = reg_status.timestamp_ms;
  868. hal.console->printf("IOMCU startup\n");
  869. return;
  870. }
  871. uint32_t dt_ms = reg_status.timestamp_ms - last_iocmu_timestamp_ms;
  872. uint32_t ts1 = last_iocmu_timestamp_ms;
  873. last_iocmu_timestamp_ms = reg_status.timestamp_ms;
  874. if (dt_ms < 500) {
  875. // all OK
  876. return;
  877. }
  878. detected_io_reset = true;
  879. AP::internalerror().error(AP_InternalError::error_t::iomcu_reset);
  880. hal.console->printf("IOMCU reset t=%u %u %u dt=%u\n",
  881. unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms));
  882. // we need to ensure the mixer data and the rates are sent over to
  883. // the IOMCU
  884. if (mixing.enabled) {
  885. trigger_event(IOEVENT_MIXING);
  886. }
  887. trigger_event(IOEVENT_SET_RATES);
  888. trigger_event(IOEVENT_SET_DEFAULT_RATE);
  889. }
  890. #endif // HAL_WITH_IO_MCU