AP_IOMCU: implement manual_rc_mask

This commit is contained in:
Andrew Tridgell 2018-10-31 15:09:49 +11:00
parent 27f06ce810
commit beff16abe6
4 changed files with 14 additions and 2 deletions

View File

@ -788,7 +788,8 @@ void AP_IOMCU::shutdown(void)
setup for mixing. This allows fixed wing aircraft to fly in manual
mode if the FMU dies
*/
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain)
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
float mixing_gain, uint16_t manual_rc_mask)
{
if (config.protocol_version != IOMCU_PROTOCOL_VERSION) {
return false;
@ -833,6 +834,7 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_
MIX_UPDATE(mixing.rc_chan_override, override_chan);
MIX_UPDATE(mixing.mixing_gain, (uint16_t)(mixing_gain*1000));
MIX_UPDATE(mixing.manual_rc_mask, manual_rc_mask);
// and enable
MIX_UPDATE(mixing.enabled, 1);

View File

@ -91,7 +91,8 @@ public:
void shutdown();
// setup for FMU failsafe mixing
bool setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain);
bool setup_mixing(RCMapper *rcmap, int8_t override_chan,
float mixing_gain, uint16_t manual_rc_mask);
private:
AP_HAL::UARTDriver &uart;

View File

@ -166,6 +166,9 @@ struct PACKED page_mixing {
// is the throttle an angle input?
uint8_t throttle_is_angle;
// mask of channels which are pure manual in override
uint16_t manual_rc_mask;
// enabled needs to be 1 to enable mixing
uint8_t enabled;

View File

@ -141,6 +141,12 @@ void AP_IOMCU_FW::run_mixer(void)
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)mixing.servo_function[i];
uint16_t &pwm = reg_direct_pwm.pwm[i];
if (mixing.manual_rc_mask & (1U<<i)) {
// treat as pass-thru if this channel is set in MANUAL_RC_MASK
function = SRV_Channel::k_manual;
}
switch (function) {
case SRV_Channel::k_manual:
pwm = rc_input.pwm[i];