Plane: fixed handling of trim for flapersons

this allows TRIM_AUTO to work for flaperons

fixes issue #1188
This commit is contained in:
Andrew Tridgell 2014-11-16 14:41:03 +11:00
parent 809ff15b43
commit 78d85dfafc

View File

@ -686,8 +686,12 @@ static void flaperon_update(int8_t flap_percent)
or from auto flaps. or from auto flaps.
*/ */
// first map the amount of aileron roll to a 1000..2000 value // first map the amount of aileron roll to a 1000..2000 value. We
ch1 = (channel_roll->pwm_to_angle_dz(0) / 9) + 1500; // center it on 1500 so that using trim on the roll channel will
// have an affect on the flaperon roll output. We also scale it
// for the roll min/max range, so that transmitters with a small
// range of outputs can command flaperons with full output range.
ch1 = 1500 + ((channel_roll->radio_out - 1500) * 1000.0f / (channel_roll->radio_max - channel_roll->radio_min));
// now map flap percentage to a 1000..2000 value // now map flap percentage to a 1000..2000 value
ch2 = 1500 - flap_percent * 5; ch2 = 1500 - flap_percent * 5;