diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde
index 3e6147b7a7a8ebc1e6bf006aa98755e505f435c2..893c739d559cfa6ecfe4f486c753177fa370db88 100644
--- a/APMrover2/APMrover2.pde
+++ b/APMrover2/APMrover2.pde
@@ -553,7 +553,7 @@ void setup() {
     // load the default values of variables listed in var_info[]
     AP_Param::setup_sketch_defaults();
 
-    rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE, 1.0);
+    rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
     vcc_pin = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
     batt_volt_pin = hal.analogin->channel(g.battery_volt_pin);
     batt_curr_pin = hal.analogin->channel(g.battery_curr_pin);
diff --git a/APMrover2/sensors.pde b/APMrover2/sensors.pde
index fdc16cff57f13d9e0a54da9b6b1c41551f623689..196db0a45abd16d4dd7525f4f8fbef59f84e2d94 100644
--- a/APMrover2/sensors.pde
+++ b/APMrover2/sensors.pde
@@ -44,7 +44,7 @@ static void read_battery(void)
 void read_receiver_rssi(void)
 {
     rssi_analog_source->set_pin(g.rssi_pin);
-    float ret = rssi_analog_source->read_average();
+    float ret = rssi_analog_source->voltage_average() * 50;
     receiver_rssi = constrain_int16(ret, 0, 255);
 }