diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h
index ca6fc18eefe46795da704b6d0101f6b4efa78cdf..d18a694602b2585b0030124febdd251062cbd320 100644
--- a/ArduPlane/Parameters.h
+++ b/ArduPlane/Parameters.h
@@ -180,6 +180,7 @@ public:
         k_param_rssi_pin,
         k_param_battery_volt_pin,   // unused
         k_param_battery_curr_pin,   // unused - 169
+        k_param_rssi_range,
 
         //
         // 170: Radio settings
@@ -411,6 +412,7 @@ public:
     AP_Int8 flap_2_percent;
     AP_Int8 flap_2_speed;
     AP_Int8 rssi_pin;
+    AP_Float rssi_range;             // allows to set max voltage for rssi pin such as 5.0, 3.3 etc.     
     AP_Int8 inverted_flight_ch;             // 0=disabled, 1-8 is channel for inverted flight trigger
     AP_Int8 stick_mixing;
     AP_Float takeoff_throttle_min_speed;
diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde
index 377376ca71b8d0f60c42f2db320b3ac0858a8632..44d716d890087681087c375c7152478681b1b628 100644
--- a/ArduPlane/Parameters.pde
+++ b/ArduPlane/Parameters.pde
@@ -753,6 +753,14 @@ const AP_Param::Info var_info[] PROGMEM = {
     // @User: Standard
     GSCALAR(rssi_pin,            "RSSI_PIN",         -1),
 
+    // @Param: RSSI_RANGE
+    // @DisplayName: Receiver RSSI voltage range
+    // @Description: Receiver RSSI voltage range
+    // @Units: Volt
+    // @Values: 3.3:3.3V, 5.0:5V
+    // @User: Standard
+    GSCALAR(rssi_range,          "RSSI_RANGE",         5.0),
+
     // @Param: INVERTEDFLT_CH
     // @DisplayName: Inverted flight channel
     // @Description: A RC input channel number to enable inverted flight. If this is non-zero then the APM will monitor the correcponding RC input channel and will enable inverted flight when the channel goes above 1750.
diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde
index 581159974309f9cf3faddfe3d77a22d4be5d7346..737e24af92337b7282e2791b761e560fde27684b 100644
--- a/ArduPlane/sensors.pde
+++ b/ArduPlane/sensors.pde
@@ -83,12 +83,16 @@ static void read_battery(void)
 // RC_CHANNELS_SCALED message
 void read_receiver_rssi(void)
 {
-    rssi_analog_source->set_pin(g.rssi_pin);
-    float ret = rssi_analog_source->voltage_average() * 50;
-    receiver_rssi = constrain_int16(ret, 0, 255);
+    // avoid divide by zero
+    if (g.rssi_range <= 0) {
+        receiver_rssi = 0;
+    }else{
+        rssi_analog_source->set_pin(g.rssi_pin);
+        float ret = rssi_analog_source->voltage_average() * 255 / g.rssi_range;
+        receiver_rssi = constrain_int16(ret, 0, 255);
+    }
 }
 
-
 /*
   return current_loc.alt adjusted for ALT_OFFSET
   This is useful during long flights to account for barometer changes