diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 37c6012e24..3b5ed6735e 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -462,6 +462,10 @@ static int16_t airspeed_nudge_cm; // 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel static int16_t throttle_nudge = 0; +// receiver RSSI +static uint8_t receiver_rssi; + + //////////////////////////////////////////////////////////////////////////////// // Ground speed //////////////////////////////////////////////////////////////////////////////// @@ -880,6 +884,8 @@ static void medium_loop() } #endif + read_receiver_rssi(); + // Read altitude from sensors // ------------------ update_alt(); diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 038999e2cf..0e8fedb644 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -301,7 +301,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan) 0, 0, 0, - receiver_rssi()); + receiver_rssi); } static void NOINLINE send_radio_in(mavlink_channel_t chan) @@ -318,7 +318,7 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan) g.rc_6.radio_in, g.rc_7.radio_in, g.rc_8.radio_in, - receiver_rssi()); + receiver_rssi); } static void NOINLINE send_radio_out(mavlink_channel_t chan) diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index c77b22ade6..9e52a5c251 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -56,17 +56,12 @@ static void read_battery(void) } -// return receiver RSSI as an 8 bit number for MAVLink +// read the receiver RSSI as an 8 bit number for MAVLink // RC_CHANNELS_SCALED message -uint8_t receiver_rssi(void) +void read_receiver_rssi(void) { #if RECEIVER_RSSI_PIN != -1 float ret = RSSI_pin.read(); - if (ret >= 255) { - return 255; - } - return (uint8_t)ret; -#else - return 0; + receiver_rssi = constrain(ret, 0, 255); #endif }