From 5d54215221abea9e7cba1dbf339bee4a047d46e9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 1 Apr 2013 22:15:45 +1100 Subject: [PATCH] Plane: use int16_t() not int() to ensure simulator matches AVR --- ArduPlane/radio.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 4701a5e1af..01c21dfb4f 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -79,8 +79,8 @@ static void read_radio() pwm_roll = ch1_temp; pwm_pitch = ch2_temp; }else{ - pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int(ch2_temp - elevon2_trim) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int(ch1_temp - elevon1_trim)) / 2 + 1500; - pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int(ch2_temp - elevon2_trim) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int(ch1_temp - elevon1_trim)) / 2 + 1500; + pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(ch2_temp - elevon2_trim) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(ch1_temp - elevon1_trim)) / 2 + 1500; + pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(ch2_temp - elevon2_trim) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(ch1_temp - elevon1_trim)) / 2 + 1500; } if (control_mode == TRAINING) {