Browse Source

Plane: use voltage_average() for RSSI

this fixes it on PX4
master
Andrew Tridgell 12 years ago
parent
commit
97b6aaac77
  1. 5
      ArduPlane/ArduPlane.pde
  2. 2
      ArduPlane/sensors.pde

5
ArduPlane/ArduPlane.pde

@ -242,8 +242,7 @@ static AP_Navigation *nav_controller = &L1_controller; @@ -242,8 +242,7 @@ static AP_Navigation *nav_controller = &L1_controller;
static AP_HAL::AnalogSource *pitot_analog_source;
// 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;
static AP_HAL::AnalogSource *vcc_pin;
@ -662,7 +661,7 @@ void setup() { @@ -662,7 +661,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, 0.25);
rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE);
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
pitot_analog_source = new AP_ADC_AnalogSource( &adc,

2
ArduPlane/sensors.pde

@ -67,7 +67,7 @@ static void read_battery(void) @@ -67,7 +67,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);
}

Loading…
Cancel
Save