mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: use voltage_average() for RSSI
this allows it to work on PX4
This commit is contained in:
parent
48cfdac6f0
commit
e1ac097e0e
@ -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);
|
||||
|
@ -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);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user