From e1ac097e0e0eba2156a3e8ab402f88d18b3b6c97 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 May 2013 15:14:23 +1000 Subject: [PATCH] Rover: use voltage_average() for RSSI this allows it to work on PX4 --- APMrover2/APMrover2.pde | 2 +- APMrover2/sensors.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index 3e6147b7a7..893c739d55 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 fdc16cff57..196db0a45a 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); }