diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 0b829f1951..de3c4448d1 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -23,13 +23,10 @@ extern const AP_HAL::HAL &hal; enum ioevents { IOEVENT_INIT=1, IOEVENT_SEND_PWM_OUT, - IOEVENT_SET_DISARMED_PWM, - IOEVENT_SET_FAILSAFE_PWM, IOEVENT_FORCE_SAFETY_OFF, IOEVENT_FORCE_SAFETY_ON, IOEVENT_SET_ONESHOT_ON, IOEVENT_SET_RATES, - IOEVENT_GET_RCIN, IOEVENT_ENABLE_SBUS, IOEVENT_SET_HEATER_TARGET, IOEVENT_SET_DEFAULT_RATE, @@ -226,7 +223,7 @@ void AP_IOMCU::thread_main(void) // update safety pwm if (pwm_out.safety_pwm_set != pwm_out.safety_pwm_sent) { uint8_t set = pwm_out.safety_pwm_set; - if (write_registers(PAGE_DISARMED_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.safety_pwm)) { + if (write_registers(PAGE_SAFETY_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.safety_pwm)) { pwm_out.safety_pwm_sent = set; } } @@ -809,6 +806,7 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan) MIX_UPDATE(mixing.servo_min[i], ch->get_output_min()); MIX_UPDATE(mixing.servo_max[i], ch->get_output_max()); MIX_UPDATE(mixing.servo_function[i], ch->get_function()); + MIX_UPDATE(mixing.servo_reversed[i], ch->get_reversed()); } // update RCMap MIX_UPDATE(mixing.rc_channel[0], rcmap->roll()); @@ -826,8 +824,18 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan) MIX_UPDATE(mixing.rc_min[i], ch->get_radio_min()); MIX_UPDATE(mixing.rc_max[i], ch->get_radio_max()); MIX_UPDATE(mixing.rc_trim[i], ch->get_radio_trim()); + MIX_UPDATE(mixing.rc_reversed[i], ch->get_reverse()); + + // cope with reversible throttle + if (i == 2 && ch->get_type() == RC_Channel::RC_CHANNEL_TYPE_ANGLE) { + MIX_UPDATE(mixing.throttle_is_angle, 1); + } else { + MIX_UPDATE(mixing.throttle_is_angle, 0); + } } + MIX_UPDATE(mixing.rc_chan_override, override_chan); + // and enable MIX_UPDATE(mixing.enabled, 1); if (changed) { diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index c66b74e444..affe46a907 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -195,6 +195,15 @@ void AP_IOMCU_FW::update() sbus_out_write(reg_servo.pwm, IOMCU_MAX_CHANNELS); } + // handle FMU failsafe + if (now - fmu_data_received_time > 10) { + // we are not getting input from the FMU. Fill in failsafe values + fill_failsafe_pwm(); + chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM)); + // mark as done + fmu_data_received_time = now; + } + // run remaining functions at 1kHz if (now != last_loop_ms) { last_loop_ms = now; @@ -208,7 +217,6 @@ void AP_IOMCU_FW::update() void AP_IOMCU_FW::pwm_out_update() { - //TODO: PWM mixing memcpy(reg_servo.pwm, reg_direct_pwm.pwm, sizeof(reg_direct_pwm)); hal.rcout->cork(); for (uint8_t i = 0; i < SERVO_COUNT; i++) { @@ -258,6 +266,14 @@ void AP_IOMCU_FW::rcin_update() hal.rcout->set_default_rate(reg_setup.pwm_defaultrate); } + // check for active override channel + if (mixing.enabled && + mixing.rc_chan_override > 0 && + mixing.rc_chan_override <= IOMCU_MAX_CHANNELS) { + override_active = (rc_input.pwm[mixing.rc_chan_override-1] >= 1800); + } else { + override_active = false; + } } void AP_IOMCU_FW::process_io_packet() @@ -457,7 +473,12 @@ bool AP_IOMCU_FW::handle_code_write() break; } break; + case PAGE_DIRECT_PWM: { + if (override_active) { + // no input when override is active + break; + } /* copy channel data */ uint8_t i = 0, offset = rx_io_packet.offset, num_values = rx_io_packet.count; while ((offset < IOMCU_MAX_CHANNELS) && (num_values > 0)) { @@ -476,12 +497,25 @@ bool AP_IOMCU_FW::handle_code_write() chEvtSignalI(thread_ctx, EVENT_MASK(IOEVENT_PWM)); break; } + case PAGE_MIXING: { uint8_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; memcpy(((uint16_t *)&mixing)+offset, &rx_io_packet.regs[0], num_values*2); break; } + case PAGE_SAFETY_PWM: { + uint8_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; + memcpy((®_safety_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2); + break; + } + + case PAGE_FAILSAFE_PWM: { + uint8_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; + memcpy((®_failsafe_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2); + break; + } + default: break; } @@ -576,6 +610,23 @@ void AP_IOMCU_FW::rcout_mode_update(void) } } +/* + fill in failsafe PWM values + */ +void AP_IOMCU_FW::fill_failsafe_pwm(void) +{ + for (uint8_t i=0; i