From c44fd42349078dfef3ae0fae92c5b4c2fe42b02a Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Mon, 13 May 2013 15:18:32 +1000
Subject: [PATCH] Copter: fixed RSSI reading on PX4

needed for different analog input scaling
---
 ArduCopter/ArduCopter.pde | 5 ++---
 ArduCopter/sensors.pde    | 2 +-
 2 files changed, 3 insertions(+), 4 deletions(-)

diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index b9545408e..f3b262ae3 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -782,8 +782,7 @@ static AP_Relay relay;
   static AP_Camera camera(&relay);
 #endif
 
-// a pin for reading the receiver RSSI voltage. The scaling by 0.25
-// is to take the 0 to 1024 range down to an 8 bit range for MAVLink
+// a pin for reading the receiver RSSI voltage.
 static AP_HAL::AnalogSource* rssi_analog_source;
 
 
@@ -878,7 +877,7 @@ void setup() {
             &sonar_mode_filter);
 #endif
 
-    rssi_analog_source      = hal.analogin->channel(g.rssi_pin, 0.25);
+    rssi_analog_source      = hal.analogin->channel(g.rssi_pin);
     batt_volt_analog_source = hal.analogin->channel(g.battery_volt_pin);
     batt_curr_analog_source = hal.analogin->channel(g.battery_curr_pin);
     board_vcc_analog_source = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC);
diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde
index e5a233280..7662d5d4b 100644
--- a/ArduCopter/sensors.pde
+++ b/ArduCopter/sensors.pde
@@ -142,6 +142,6 @@ static void read_battery(void)
 void read_receiver_rssi(void)
 {
     rssi_analog_source->set_pin(g.rssi_pin);
-    float ret = rssi_analog_source->read_latest();
+    float ret = rssi_analog_source->voltage_average() * 50;
     receiver_rssi = constrain_int16(ret, 0, 255);
 }
-- 
GitLab