ELEVON_OUTPUT and TRIM

I was having trouble with ELEVON_OUTPUT and TRIM (see here ELEVON_OUTPUT and RC_TRIM)

Looking through the code, in ArduPlane/servos.cpp

/*
output mixer based on two channel output types
*/
void Plane::channel_output_mixer(uint8_t mixing_type, SRV_Channel::Aux_servo_function_t func1, SRV_Channel::Aux_servo_function_t func2)
{

chan1->set_output_pwm(chan1_out);
chan2->set_output_pwm(chan2_out);

}

Is there any reason that the last two line here do not call “set_output_pwm_trimmed” instead? I haven’t tested it yet, but it looks like this would yield the desired functionality.

Seems what I needed to try my idea was,

SRV_Channels::set_output_pwm_trimmed(SRV_Channel::func1, chan1_out);
SRV_Channels::set_output_pwm_trimmed(SRV_Channel::func2, chan2_out);

However, the behavior wasn’t what I expected; I realise now that there is some unintended mixing between the elevator and aileron channels when in manual mode, as they are assumed to be passthrough, but are actually mixed when ELEVON_OUTPUT is configured, and that mixing assumes a 1500 centre (trim) value, which may not be correct.