diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde
index a49b0e1954d2450ddd18a972257963a0457dcbdf..6266040b4da333a193cd59f49c6b9a2aadcccc38 100644
--- a/ArduPlane/Attitude.pde
+++ b/ArduPlane/Attitude.pde
@@ -684,34 +684,21 @@ static void flaperon_update(int8_t flap_percent)
       flaperons are implemented as a mixer between aileron and a
       percentage of flaps. Flap input can come from a manual channel
       or from auto flaps.
-     */
-
-    // first map the amount of aileron roll to a 1000..2000 value. We
-    // 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
+      Use k_flaperon1 and k_flaperon2 channel trims to center servos.
+      Then adjust aileron trim for level flight (note that aileron trim is affected
+      by mixing gain). flapin_channel's trim is not used.
+     */
+     
+    ch1 = channel_roll->radio_out;
+    // The *5 is to take a percentage to a value from -500 to 500 for the mixer
     ch2 = 1500 - flap_percent * 5;
-
-    // run the mixer
     channel_output_mixer(g.flaperon_output, ch1, ch2);
-
-    // the mixer gives us a value from 900 to 2100 for each channel We
-    // now need to map that onto a -4500 to 4500 angle. We use a ratio
-    // of 9 so that for a MIXING_GAIN of 1.0 we get pass-thru of
-    // ailerons with no flaps
-    ch1 = (ch1 - 1500) * 9;
-    ch2 = (ch2 - 1500) * 9;
-
-    // and now let the trims and ranges of the flaperon output
-    // channels take effect to map this to PWM values
-    RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flaperon1, ch1);
-    RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flaperon2, ch2);
+    RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::k_flaperon1, ch1);
+    RC_Channel_aux::set_radio_trimmed(RC_Channel_aux::k_flaperon2, ch2);
 }
 
+
 /*****************************************
 * Set the flight control servos based on the current calculated values
 *****************************************/