Browse Source

Plane: use int16_t() not int() to ensure simulator matches AVR

master
Andrew Tridgell 12 years ago
parent
commit
5d54215221
  1. 4
      ArduPlane/radio.pde

4
ArduPlane/radio.pde

@ -79,8 +79,8 @@ static void read_radio() @@ -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) {

Loading…
Cancel
Save