diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index b9545408ee0d665fc27ab890c4693eeeac538503..f3b262ae37af29ed2f549a9f2fe2c854d6c31923 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 e5a233280641646ed0497aa4ef71772d7f0ebec7..7662d5d4b0f3554eb51d9b2de8294c693d446dd7 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); }