APM:Libraries
AP_IOMCU.cpp
Go to the documentation of this file.
1 /*
2  implement protocol for controlling an IO microcontroller
3 
4  For bootstrapping this will initially implement the px4io protocol,
5  but will later move to an ArduPilot specific protocol
6  */
7 
8 #include "AP_IOMCU.h"
9 
10 #if HAL_WITH_IO_MCU
11 
12 #include <AP_Math/AP_Math.h>
13 #include <AP_Math/crc.h>
15 #include <AP_ROMFS/AP_ROMFS.h>
16 #include <AP_Math/crc.h>
17 
18 extern const AP_HAL::HAL &hal;
19 
20 #define PKT_MAX_REGS 32
21 
22 //#define IOMCU_DEBUG
23 
24 struct PACKED IOPacket {
25  uint8_t count:6;
26  uint8_t code:2;
27  uint8_t crc;
28  uint8_t page;
29  uint8_t offset;
30  uint16_t regs[PKT_MAX_REGS];
31 
32  // get packet size in bytes
33  uint8_t get_size(void) const {
34  return count*2 + 4;
35  }
36 };
37 
38 /*
39  values for pkt.code
40  */
41 enum iocode {
42  // read types
43  CODE_READ = 0,
44  CODE_WRITE = 1,
45 
46  // reply codes
47  CODE_SUCCESS = 0,
48  CODE_CORRUPT = 1,
49  CODE_ERROR = 2
50 };
51 
52 // IO pages
53 enum iopage {
54  PAGE_CONFIG = 0,
55  PAGE_STATUS = 1,
56  PAGE_ACTUATORS = 2,
57  PAGE_SERVOS = 3,
58  PAGE_RAW_RCIN = 4,
59  PAGE_RCIN = 5,
60  PAGE_RAW_ADC = 6,
61  PAGE_PWM_INFO = 7,
62  PAGE_SETUP = 50,
63  PAGE_DIRECT_PWM = 54,
64  PAGE_DISARMED_PWM = 108,
65 };
66 
67 // pending IO events to send, used as an event mask
68 enum ioevents {
69  IOEVENT_INIT=1,
70  IOEVENT_SEND_PWM_OUT,
71  IOEVENT_SET_DISARMED_PWM,
72  IOEVENT_SET_FAILSAFE_PWM,
73  IOEVENT_FORCE_SAFETY_OFF,
74  IOEVENT_FORCE_SAFETY_ON,
75  IOEVENT_SET_ONESHOT_ON,
76  IOEVENT_SET_RATES,
77  IOEVENT_GET_RCIN,
78  IOEVENT_ENABLE_SBUS,
79  IOEVENT_SET_HEATER_TARGET,
80  IOEVENT_SET_DEFAULT_RATE,
81  IOEVENT_SET_SAFETY_MASK,
82 };
83 
84 // setup page registers
85 #define PAGE_REG_SETUP_FEATURES 0
86 #define P_SETUP_FEATURES_SBUS1_OUT 1
87 #define P_SETUP_FEATURES_SBUS2_OUT 2
88 #define P_SETUP_FEATURES_PWM_RSSI 4
89 #define P_SETUP_FEATURES_ADC_RSSI 8
90 #define P_SETUP_FEATURES_ONESHOT 16
91 
92 #define PAGE_REG_SETUP_ARMING 1
93 #define P_SETUP_ARMING_IO_ARM_OK (1<<0)
94 #define P_SETUP_ARMING_FMU_ARMED (1<<1)
95 #define P_SETUP_ARMING_RC_HANDLING_DISABLED (1<<6)
96 #define P_SETUP_ARMING_SAFETY_DISABLE_ON (1 << 11) // disable use of safety button for safety off->on
97 #define P_SETUP_ARMING_SAFETY_DISABLE_OFF (1 << 12) // disable use of safety button for safety on->off
98 
99 #define PAGE_REG_SETUP_PWM_RATE_MASK 2
100 #define PAGE_REG_SETUP_DEFAULTRATE 3
101 #define PAGE_REG_SETUP_ALTRATE 4
102 #define PAGE_REG_SETUP_REBOOT_BL 10
103 #define PAGE_REG_SETUP_CRC 11
104 #define PAGE_REG_SETUP_SBUS_RATE 19
105 #define PAGE_REG_SETUP_IGNORE_SAFETY 20 /* bitmask of surfaces to ignore the safety status */
106 #define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21
107 
108 // magic value for rebooting to bootloader
109 #define REBOOT_BL_MAGIC 14662
110 
111 #define PAGE_REG_SETUP_FORCE_SAFETY_OFF 12
112 #define PAGE_REG_SETUP_FORCE_SAFETY_ON 14
113 #define FORCE_SAFETY_MAGIC 22027
114 
115 AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) :
116  uart(_uart)
117 {}
118 
119 /*
120  initialise library, starting thread
121  */
122 void AP_IOMCU::init(void)
123 {
124  //upload_fw(fw_name);
125 
126  // uart runs at 1.5MBit
127  uart.begin(1500*1000, 256, 256);
128  uart.set_blocking_writes(false);
129  uart.set_unbuffered_writes(true);
130 
131  // check IO firmware CRC
132  hal.scheduler->delay(2000);
133 
134  check_crc();
135 
136  thread_ctx = chThdCreateFromHeap(NULL,
137  THD_WORKING_AREA_SIZE(1024),
138  "IOMCU",
139  183,
140  thread_start,
141  this);
142  if (thread_ctx == nullptr) {
143  AP_HAL::panic("Unable to allocate IOMCU thread");
144  }
145 }
146 
147 /*
148  static function to enter thread_main()
149  */
150 void AP_IOMCU::thread_start(void *ctx)
151 {
152  ((AP_IOMCU *)ctx)->thread_main();
153 }
154 
155 /*
156  handle event failure
157  */
158 void AP_IOMCU::event_failed(uint8_t event)
159 {
160  // wait 0.5ms then retry
161  hal.scheduler->delay_microseconds(500);
162  trigger_event(event);
163 }
164 
165 /*
166  main IO thread loop
167  */
168 void AP_IOMCU::thread_main(void)
169 {
170  thread_ctx = chThdGetSelfX();
171 
172  uart.begin(1500*1000, 256, 256);
173  uart.set_blocking_writes(false);
174  uart.set_unbuffered_writes(true);
175 
176  trigger_event(IOEVENT_INIT);
177 
178  while (true) {
179  eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(10));
180 
181  // check for pending IO events
182  if (mask & EVENT_MASK(IOEVENT_SEND_PWM_OUT)) {
183  send_servo_out();
184  }
185 
186  if (mask & EVENT_MASK(IOEVENT_INIT)) {
187  // set IO_ARM_OK and FMU_ARMED
188  if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, 0,
189  P_SETUP_ARMING_IO_ARM_OK |
190  P_SETUP_ARMING_FMU_ARMED |
191  P_SETUP_ARMING_RC_HANDLING_DISABLED)) {
192  event_failed(IOEVENT_INIT);
193  continue;
194  }
195  }
196 
197 
198  if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_OFF)) {
199  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_OFF, FORCE_SAFETY_MAGIC)) {
200  event_failed(IOEVENT_FORCE_SAFETY_OFF);
201  continue;
202  }
203  }
204 
205  if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_ON)) {
206  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_ON, FORCE_SAFETY_MAGIC)) {
207  event_failed(IOEVENT_FORCE_SAFETY_ON);
208  continue;
209  }
210  }
211 
212 
213  if (mask & EVENT_MASK(IOEVENT_SET_RATES)) {
214  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) ||
215  !write_register(PAGE_SETUP, PAGE_REG_SETUP_PWM_RATE_MASK, rate.chmask)) {
216  event_failed(IOEVENT_SET_RATES);
217  continue;
218  }
219  }
220 
221  if (mask & EVENT_MASK(IOEVENT_ENABLE_SBUS)) {
222  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_SBUS_RATE, rate.sbus_rate_hz) ||
223  !modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0,
224  P_SETUP_FEATURES_SBUS1_OUT)) {
225  event_failed(IOEVENT_ENABLE_SBUS);
226  continue;
227  }
228  }
229 
230  if (mask & EVENT_MASK(IOEVENT_SET_HEATER_TARGET)) {
231  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_HEATER_DUTY_CYCLE, heater_duty_cycle)) {
232  event_failed(IOEVENT_SET_HEATER_TARGET);
233  continue;
234  }
235  }
236 
237  if (mask & EVENT_MASK(IOEVENT_SET_DEFAULT_RATE)) {
238  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_DEFAULTRATE, rate.default_freq)) {
239  event_failed(IOEVENT_SET_DEFAULT_RATE);
240  continue;
241  }
242  }
243 
244  if (mask & EVENT_MASK(IOEVENT_SET_ONESHOT_ON)) {
245  if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_ONESHOT)) {
246  event_failed(IOEVENT_SET_ONESHOT_ON);
247  continue;
248  }
249  }
250 
251  if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) {
252  if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) {
253  event_failed(IOEVENT_SET_SAFETY_MASK);
254  continue;
255  }
256  }
257 
258  // check for regular timed events
259  uint32_t now = AP_HAL::millis();
260  if (now - last_rc_read_ms > 20) {
261  // read RC input at 50Hz
262  read_rc_input();
263  last_rc_read_ms = AP_HAL::millis();
264  }
265 
266  if (now - last_status_read_ms > 50) {
267  // read status at 20Hz
268  read_status();
269  last_status_read_ms = AP_HAL::millis();
270  }
271 
272  if (now - last_servo_read_ms > 50) {
273  // read servo out at 20Hz
274  read_servo();
275  last_servo_read_ms = AP_HAL::millis();
276  }
277 
278 #ifdef IOMCU_DEBUG
279  if (now - last_debug_ms > 1000) {
280  print_debug();
281  last_debug_ms = AP_HAL::millis();
282  }
283 #endif // IOMCU_DEBUG
284 
285  if (now - last_safety_option_check_ms > 1000) {
286  update_safety_options();
287  last_safety_option_check_ms = now;
288  }
289 
290  // update safety pwm
291  if (pwm_out.safety_pwm_set != pwm_out.safety_pwm_sent) {
292  uint8_t set = pwm_out.safety_pwm_set;
293  write_registers(PAGE_DISARMED_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.safety_pwm);
294  pwm_out.safety_pwm_sent = set;
295  }
296  }
297 }
298 
299 /*
300  send servo output data
301  */
302 void AP_IOMCU::send_servo_out()
303 {
304  if (pwm_out.num_channels > 0) {
305  uint8_t n = pwm_out.num_channels;
306  if (rate.sbus_rate_hz == 0) {
307  n = MIN(n, 8);
308  }
309  uint32_t now = AP_HAL::micros();
310  if (now - last_servo_out_us >= 2000) {
311  // don't send data at more than 500Hz
312  write_registers(PAGE_DIRECT_PWM, 0, n, pwm_out.pwm);
313  last_servo_out_us = now;
314  }
315  }
316 }
317 
318 /*
319  read RC input
320  */
321 void AP_IOMCU::read_rc_input()
322 {
323  // read a min of 9 channels and max of IOMCU_MAX_CHANNELS
324  uint8_t n = MIN(MAX(9, rc_input.count), IOMCU_MAX_CHANNELS);
325  read_registers(PAGE_RAW_RCIN, 0, 6+n, (uint16_t *)&rc_input);
326  if (rc_input.flags_rc_ok) {
327  rc_input.last_input_us = AP_HAL::micros();
328  }
329 }
330 
331 /*
332  read status registers
333  */
334 void AP_IOMCU::read_status()
335 {
336  uint16_t *r = (uint16_t *)&reg_status;
337  read_registers(PAGE_STATUS, 0, sizeof(reg_status)/2, r);
338 }
339 
340 /*
341  read servo output values
342  */
343 void AP_IOMCU::read_servo()
344 {
345  if (pwm_out.num_channels > 0) {
346  read_registers(PAGE_SERVOS, 0, pwm_out.num_channels, pwm_in.pwm);
347  }
348 }
349 
350 
351 /*
352  discard any pending input
353  */
354 void AP_IOMCU::discard_input(void)
355 {
356  uint32_t n = uart.available();
357  while (n--) {
358  uart.read();
359  }
360 }
361 
362 
363 /*
364  read count 16 bit registers
365 */
366 bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint16_t *regs)
367 {
368  IOPacket pkt;
369 
370  discard_input();
371 
372  memset(&pkt.regs[0], 0, count*2);
373 
374  pkt.code = CODE_READ;
375  pkt.count = count;
376  pkt.page = page;
377  pkt.offset = offset;
378  pkt.crc = 0;
379 
380  /*
381  the protocol is a bit strange, as it unnecessarily sends the
382  same size packet that it expects to receive. This means reading
383  a large number of registers wastes a lot of serial bandwidth
384  */
385  pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
386  if (uart.write((uint8_t *)&pkt, pkt.get_size()) != pkt.get_size()) {
387  return false;
388  }
389 
390  // wait for the expected number of reply bytes or timeout
391  if (!uart.wait_timeout(count*2+4, 10)) {
392  return false;
393  }
394 
395  uint8_t *b = (uint8_t *)&pkt;
396  uint8_t n = uart.available();
397  for (uint8_t i=0; i<n; i++) {
398  if (i < sizeof(pkt)) {
399  b[i] = uart.read();
400  }
401  }
402 
403  uint8_t got_crc = pkt.crc;
404  pkt.crc = 0;
405  uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
406  if (got_crc != expected_crc) {
407  hal.console->printf("bad crc %02x should be %02x n=%u %u/%u/%u\n",
408  got_crc, expected_crc,
409  n, page, offset, count);
410  return false;
411  }
412 
413  if (pkt.code != CODE_SUCCESS) {
414  hal.console->printf("bad code %02x read %u/%u/%u\n", pkt.code, page, offset, count);
415  return false;
416  }
417  if (pkt.count < count) {
418  hal.console->printf("bad count %u read %u/%u/%u n=%u\n", pkt.count, page, offset, count, n);
419  return false;
420  }
421  memcpy(regs, pkt.regs, count*2);
422  return true;
423 }
424 
425 /*
426  write count 16 bit registers
427 */
428 bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs)
429 {
430  IOPacket pkt;
431 
432  discard_input();
433 
434  memset(&pkt.regs[0], 0, count*2);
435 
436  pkt.code = CODE_WRITE;
437  pkt.count = count;
438  pkt.page = page;
439  pkt.offset = offset;
440  pkt.crc = 0;
441  memcpy(pkt.regs, regs, 2*count);
442  pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
443  if (uart.write((uint8_t *)&pkt, pkt.get_size()) != pkt.get_size()) {
444  return false;
445  }
446 
447  // wait for the expected number of reply bytes or timeout
448  if (!uart.wait_timeout(4, 10)) {
449  //hal.console->printf("no reply for %u/%u/%u\n", page, offset, count);
450  return false;
451  }
452 
453  uint8_t *b = (uint8_t *)&pkt;
454  uint8_t n = uart.available();
455  for (uint8_t i=0; i<n; i++) {
456  if (i < sizeof(pkt)) {
457  b[i] = uart.read();
458  }
459  }
460 
461  if (pkt.code != CODE_SUCCESS) {
462  hal.console->printf("bad code %02x write %u/%u/%u %02x/%02x n=%u\n",
463  pkt.code, page, offset, count,
464  pkt.page, pkt.offset, n);
465  return false;
466  }
467  uint8_t got_crc = pkt.crc;
468  pkt.crc = 0;
469  uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
470  if (got_crc != expected_crc) {
471  hal.console->printf("bad crc %02x should be %02x\n", got_crc, expected_crc);
472  return false;
473  }
474  return true;
475 }
476 
477 // modify a single register
478 bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits)
479 {
480  uint16_t v = 0;
481  if (!read_registers(page, offset, 1, &v)) {
482  return false;
483  }
484  uint16_t v2 = (v & ~clearbits) | setbits;
485  if (v2 == v) {
486  return true;
487  }
488  return write_registers(page, offset, 1, &v2);
489 }
490 
491 void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm)
492 {
493  if (chan >= IOMCU_MAX_CHANNELS) {
494  return;
495  }
496  if (chan >= pwm_out.num_channels) {
497  pwm_out.num_channels = chan+1;
498  }
499  pwm_out.pwm[chan] = pwm;
500  if (!corked) {
501  push();
502  }
503 }
504 
505 void AP_IOMCU::print_debug(void)
506 {
507 #ifdef IOMCU_DEBUG
508  const uint16_t *r = (const uint16_t *)&reg_status;
509  for (uint8_t i=0; i<sizeof(reg_status)/2; i++) {
510  hal.console->printf("%04x ", r[i]);
511  }
512  hal.console->printf("\n");
513 #endif // IOMCU_DEBUG
514 }
515 
516 // trigger an ioevent
517 void AP_IOMCU::trigger_event(uint8_t event)
518 {
519  if (thread_ctx != nullptr) {
520  chEvtSignal(thread_ctx, EVENT_MASK(event));
521  }
522 }
523 
524 // get state of safety switch
525 AP_HAL::Util::safety_state AP_IOMCU::get_safety_switch_state(void) const
526 {
527  return reg_status.flag_safety_off?AP_HAL::Util::SAFETY_ARMED:AP_HAL::Util::SAFETY_DISARMED;
528 }
529 
530 // force safety on
531 bool AP_IOMCU::force_safety_on(void)
532 {
533  trigger_event(IOEVENT_FORCE_SAFETY_ON);
534  return true;
535 }
536 
537 // force safety off
538 void AP_IOMCU::force_safety_off(void)
539 {
540  trigger_event(IOEVENT_FORCE_SAFETY_OFF);
541 }
542 
543 // read from one channel
544 uint16_t AP_IOMCU::read_channel(uint8_t chan)
545 {
546  return pwm_in.pwm[chan];
547 }
548 
549 // cork output
550 void AP_IOMCU::cork(void)
551 {
552  corked = true;
553 }
554 
555 // push output
556 void AP_IOMCU::push(void)
557 {
558  trigger_event(IOEVENT_SEND_PWM_OUT);
559  corked = false;
560 }
561 
562 // set output frequency
563 void AP_IOMCU::set_freq(uint16_t chmask, uint16_t freq)
564 {
565  rate.freq = freq;
566  rate.chmask = chmask;
567  trigger_event(IOEVENT_SET_RATES);
568 }
569 
570 // get output frequency
571 uint16_t AP_IOMCU::get_freq(uint16_t chan)
572 {
573  if ((1U<<chan) & rate.chmask) {
574  return rate.freq;
575  }
576  return rate.default_freq;
577 }
578 
579 // enable SBUS out
580 bool AP_IOMCU::enable_sbus_out(uint16_t rate_hz)
581 {
582  rate.sbus_rate_hz = rate_hz;
583  trigger_event(IOEVENT_ENABLE_SBUS);
584  return true;
585 }
586 
587 /*
588  check for new RC input
589 */
590 bool AP_IOMCU::check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_chan)
591 {
592  if (last_frame_us != rc_input.last_input_us) {
593  num_channels = MIN(MIN(rc_input.count, IOMCU_MAX_CHANNELS), max_chan);
594  memcpy(channels, rc_input.pwm, num_channels*2);
595  last_frame_us = rc_input.last_input_us;
596  return true;
597  }
598  return false;
599 }
600 
601 // set IMU heater target
602 void AP_IOMCU::set_heater_duty_cycle(uint8_t duty_cycle)
603 {
604  heater_duty_cycle = duty_cycle;
605  trigger_event(IOEVENT_SET_HEATER_TARGET);
606 }
607 
608 // set default output rate
609 void AP_IOMCU::set_default_rate(uint16_t rate_hz)
610 {
611  if (rate.default_freq != rate_hz) {
612  rate.default_freq = rate_hz;
613  trigger_event(IOEVENT_SET_DEFAULT_RATE);
614  }
615 }
616 
617 // setup for oneshot mode
618 void AP_IOMCU::set_oneshot_mode(void)
619 {
620  trigger_event(IOEVENT_SET_ONESHOT_ON);
621 }
622 
623 // handling of BRD_SAFETYOPTION parameter
624 void AP_IOMCU::update_safety_options(void)
625 {
627  if (!boardconfig) {
628  return;
629  }
630  uint16_t desired_options = 0;
631  uint16_t options = boardconfig->get_safety_button_options();
633  desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_OFF;
634  }
636  desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_ON;
637  }
639  desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
640  }
641  if (last_safety_options != desired_options) {
642  uint16_t mask = (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
643  uint32_t bits_to_set = desired_options & mask;
644  uint32_t bits_to_clear = (~desired_options) & mask;
645  if (modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, bits_to_clear, bits_to_set)) {
646  last_safety_options = desired_options;
647  }
648  }
649 }
650 
651 /*
652  check ROMFS firmware against CRC on IOMCU, and if incorrect then upload new firmware
653  */
654 bool AP_IOMCU::check_crc(void)
655 {
656  // flash size minus 4k bootloader
657  const uint32_t flash_size = 0x10000 - 0x1000;
658  uint32_t fw_size;
659 
660  fw = AP_ROMFS::find_file(fw_name, fw_size);
661  if (!fw) {
662  hal.console->printf("failed to find %s\n", fw_name);
663  return false;
664  }
665  uint32_t crc = crc_crc32(0, fw, fw_size);
666 
667  // pad to max size
668  while (fw_size < flash_size) {
669  uint8_t b = 0xff;
670  crc = crc_crc32(crc, &b, 1);
671  fw_size++;
672  }
673 
674  uint32_t io_crc = 0;
675  if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc) &&
676  io_crc == crc) {
677  hal.console->printf("IOMCU: CRC ok\n");
678  crc_is_ok = true;
679  return true;
680  }
681 
682  const uint16_t magic = REBOOT_BL_MAGIC;
683  write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
684  hal.scheduler->delay(100);
685  upload_fw(fw_name);
686 
687  return false;
688 }
689 
690 /*
691  set the pwm to use when safety is on
692  */
693 void AP_IOMCU::set_safety_pwm(uint16_t chmask, uint16_t period_us)
694 {
695  bool changed = false;
696  for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
697  if (chmask & (1U<<i)) {
698  if (pwm_out.safety_pwm[i] != period_us) {
699  pwm_out.safety_pwm[i] = period_us;
700  changed = true;
701  }
702  }
703  }
704  if (changed) {
705  pwm_out.safety_pwm_set++;
706  }
707 }
708 
709 
710 // set mask of channels that ignore safety state
711 void AP_IOMCU::set_safety_mask(uint16_t chmask)
712 {
713  if (pwm_out.safety_mask != chmask) {
714  pwm_out.safety_mask = chmask;
715  trigger_event(IOEVENT_SET_SAFETY_MASK);
716  }
717 }
718 
719 /*
720  check that IO is healthy. This should be used in arming checks
721  */
722 bool AP_IOMCU::healthy(void)
723 {
724  // for now just check CRC
725  return crc_is_ok;
726 }
727 
728 #endif // HAL_WITH_IO_MCU
uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size)
Definition: crc.cpp:140
bool get_soft_armed() const
Definition: Util.h:15
uint8_t crc
uint16_t regs[PKT_MAX_REGS]
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static AP_BoardConfig * get_instance(void)
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
Definition: crc.cpp:50
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define PKT_MAX_REGS
static uint16_t pwm
Definition: RCOutput.cpp:20
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
#define MIN(a, b)
Definition: usb_conf.h:215
uint8_t page
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint32_t millis()
Definition: system.cpp:157
float v
Definition: Printf.cpp:15
safety_state
Definition: Util.h:35
#define NULL
Definition: hal_types.h:59
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
void init()
Generic board initialization function.
Definition: system.cpp:136
virtual void delay_microseconds(uint16_t us)=0
static const uint8_t * find_file(const char *name, uint32_t &size)
Definition: AP_ROMFS.cpp:30
#define PACKED
Definition: AP_Common.h:28
uint8_t offset
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint16_t get_safety_button_options(void)
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114