20 #define PKT_MAX_REGS 32    33     uint8_t get_size(
void)
 const {
    64     PAGE_DISARMED_PWM = 108,
    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,
    79     IOEVENT_SET_HEATER_TARGET,
    80     IOEVENT_SET_DEFAULT_RATE,
    81     IOEVENT_SET_SAFETY_MASK,
    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    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    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    106 #define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21   109 #define REBOOT_BL_MAGIC 14662   111 #define PAGE_REG_SETUP_FORCE_SAFETY_OFF 12   112 #define PAGE_REG_SETUP_FORCE_SAFETY_ON  14   113 #define FORCE_SAFETY_MAGIC 22027   127     uart.begin(1500*1000, 256, 256);
   128     uart.set_blocking_writes(
false);
   129     uart.set_unbuffered_writes(
true);
   136     thread_ctx = chThdCreateFromHeap(
NULL,
   137                                      THD_WORKING_AREA_SIZE(1024),
   142     if (thread_ctx == 
nullptr) {
   150 void AP_IOMCU::thread_start(
void *ctx)
   152     ((AP_IOMCU *)ctx)->thread_main();
   158 void AP_IOMCU::event_failed(uint8_t event)
   162     trigger_event(event);
   168 void AP_IOMCU::thread_main(
void)
   170     thread_ctx = chThdGetSelfX();
   172     uart.begin(1500*1000, 256, 256);
   173     uart.set_blocking_writes(
false);
   174     uart.set_unbuffered_writes(
true);
   176     trigger_event(IOEVENT_INIT);
   179         eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(10));
   182         if (mask & EVENT_MASK(IOEVENT_SEND_PWM_OUT)) {
   186         if (mask & EVENT_MASK(IOEVENT_INIT)) {
   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);
   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);
   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);
   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);
   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);
   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);
   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);
   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);
   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);
   260         if (now - last_rc_read_ms > 20) {
   266         if (now - last_status_read_ms > 50) {
   272         if (now - last_servo_read_ms > 50) {
   279         if (now - last_debug_ms > 1000) {
   283 #endif // IOMCU_DEBUG   285         if (now - last_safety_option_check_ms > 1000) {
   286             update_safety_options();
   287             last_safety_option_check_ms = now;
   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;
   302 void AP_IOMCU::send_servo_out()
   304     if (pwm_out.num_channels > 0) {
   305         uint8_t n = pwm_out.num_channels;
   306         if (rate.sbus_rate_hz == 0) {
   310         if (now - last_servo_out_us >= 2000) {
   312             write_registers(PAGE_DIRECT_PWM, 0, n, pwm_out.pwm);
   313             last_servo_out_us = now;
   321 void AP_IOMCU::read_rc_input()
   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) {
   334 void AP_IOMCU::read_status()
   336     uint16_t *r = (uint16_t *)®_status;
   337     read_registers(PAGE_STATUS, 0, 
sizeof(reg_status)/2, r);
   343 void AP_IOMCU::read_servo()
   345     if (pwm_out.num_channels > 0) {
   346         read_registers(PAGE_SERVOS, 0, pwm_out.num_channels, pwm_in.pwm);
   354 void AP_IOMCU::discard_input(
void)
   356     uint32_t n = uart.available();
   366 bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t 
count, uint16_t *regs)
   372     memset(&pkt.
regs[0], 0, count*2);
   374     pkt.code = CODE_READ;
   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()) {
   391     if (!uart.wait_timeout(count*2+4, 10)) {
   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)) {
   403     uint8_t got_crc = pkt.crc;
   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);
   413     if (pkt.code != CODE_SUCCESS) {
   414         hal.
console->
printf(
"bad code %02x read %u/%u/%u\n", pkt.code, page, offset, count);
   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);
   421     memcpy(regs, pkt.regs, count*2);
   428 bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, 
const uint16_t *regs)
   434     memset(&pkt.
regs[0], 0, count*2);
   436     pkt.code = CODE_WRITE;
   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()) {
   448     if (!uart.wait_timeout(4, 10)) {
   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)) {
   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);
   467     uint8_t got_crc = pkt.crc;
   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);
   478 bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits)
   481     if (!read_registers(page, offset, 1, &v)) {
   484     uint16_t v2 = (v & ~clearbits) | setbits;
   488     return write_registers(page, offset, 1, &v2);
   491 void AP_IOMCU::write_channel(uint8_t 
chan, uint16_t 
pwm)
   493     if (chan >= IOMCU_MAX_CHANNELS) {
   496     if (chan >= pwm_out.num_channels) {
   497         pwm_out.num_channels = chan+1;
   505 void AP_IOMCU::print_debug(
void)
   508     const uint16_t *r = (
const uint16_t *)®_status;
   509     for (uint8_t i=0; i<
sizeof(reg_status)/2; i++) {
   513 #endif // IOMCU_DEBUG   517 void AP_IOMCU::trigger_event(uint8_t event)
   519     if (thread_ctx != 
nullptr) {
   520         chEvtSignal(thread_ctx, EVENT_MASK(event));
   531 bool AP_IOMCU::force_safety_on(
void)
   533     trigger_event(IOEVENT_FORCE_SAFETY_ON);
   538 void AP_IOMCU::force_safety_off(
void)
   540     trigger_event(IOEVENT_FORCE_SAFETY_OFF);
   544 uint16_t AP_IOMCU::read_channel(uint8_t chan)
   546     return pwm_in.pwm[
chan];
   550 void AP_IOMCU::cork(
void)
   556 void AP_IOMCU::push(
void)
   558     trigger_event(IOEVENT_SEND_PWM_OUT);
   563 void AP_IOMCU::set_freq(uint16_t chmask, uint16_t freq)
   566     rate.chmask = chmask;
   567     trigger_event(IOEVENT_SET_RATES);
   571 uint16_t AP_IOMCU::get_freq(uint16_t chan)
   573     if ((1U<<chan) & rate.chmask) {
   576     return rate.default_freq;
   580 bool AP_IOMCU::enable_sbus_out(uint16_t rate_hz)
   582     rate.sbus_rate_hz = rate_hz;
   583     trigger_event(IOEVENT_ENABLE_SBUS);
   590 bool AP_IOMCU::check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *
channels, uint8_t max_chan)
   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;
   602 void AP_IOMCU::set_heater_duty_cycle(uint8_t duty_cycle)
   604     heater_duty_cycle = duty_cycle;
   605     trigger_event(IOEVENT_SET_HEATER_TARGET);
   609 void AP_IOMCU::set_default_rate(uint16_t rate_hz)
   611     if (rate.default_freq != rate_hz) {
   612         rate.default_freq = rate_hz;
   613         trigger_event(IOEVENT_SET_DEFAULT_RATE);
   618 void AP_IOMCU::set_oneshot_mode(
void)
   620     trigger_event(IOEVENT_SET_ONESHOT_ON);
   624 void AP_IOMCU::update_safety_options(
void)
   630     uint16_t desired_options = 0;
   633         desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_OFF;
   636         desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_ON;
   639         desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
   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;
   654 bool AP_IOMCU::check_crc(
void)
   657     const uint32_t flash_size = 0x10000 - 0x1000;
   665     uint32_t crc = 
crc_crc32(0, fw, fw_size);
   668     while (fw_size < flash_size) {
   675     if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc) &&
   682     const uint16_t magic = REBOOT_BL_MAGIC;
   683     write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
   693 void AP_IOMCU::set_safety_pwm(uint16_t chmask, uint16_t period_us)
   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;
   705         pwm_out.safety_pwm_set++;
   711 void AP_IOMCU::set_safety_mask(uint16_t chmask)
   713     if (pwm_out.safety_mask != chmask) {
   714         pwm_out.safety_mask = chmask;
   715         trigger_event(IOEVENT_SET_SAFETY_MASK);        
   722 bool AP_IOMCU::healthy(
void)
   728 #endif // HAL_WITH_IO_MCU uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size)
 
bool get_soft_armed() const
 
uint16_t regs[PKT_MAX_REGS]
 
AP_HAL::UARTDriver * console
 
static AP_BoardConfig * get_instance(void)
 
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
 
static uint16_t channels[SRXL_MAX_CHANNELS]
 
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
 
virtual void delay(uint16_t ms)=0
 
virtual void printf(const char *,...) FMT_PRINTF(2
 
AP_HAL::AnalogSource * chan
 
void init()
Generic board initialization function. 
 
virtual void delay_microseconds(uint16_t us)=0
 
static const uint8_t * find_file(const char *name, uint32_t &size)
 
void panic(const char *errormsg,...) FMT_PRINTF(1
 
uint16_t get_safety_button_options(void)
 
AP_HAL::Scheduler * scheduler