Browse Source

Rover: implement RSSI_PIN

route RSSI value from receiver to MAVLink
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
af141c2487
  1. 2
      APMrover2/APMrover2.pde
  2. 9
      APMrover2/sensors.pde

2
APMrover2/APMrover2.pde

@ -702,6 +702,8 @@ static void medium_loop() @@ -702,6 +702,8 @@ static void medium_loop()
case 2:
medium_loopCounter++;
read_receiver_rssi();
// perform next command
// --------------------
update_commands();

9
APMrover2/sensors.pde

@ -36,3 +36,12 @@ static void read_battery(void) @@ -36,3 +36,12 @@ static void read_battery(void)
}
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
void read_receiver_rssi(void)
{
rssi_analog_source->set_pin(g.rssi_pin);
float ret = rssi_analog_source->read_average();
receiver_rssi = constrain_int16(ret, 0, 255);
}

Loading…
Cancel
Save