mirror of https://github.com/ArduPilot/ardupilot
APM: added RSSI to RC_CHANNELS_RAW as well
and prevent double read
This commit is contained in:
parent
279e942581
commit
56ada1a69c
|
@ -462,6 +462,10 @@ static int16_t airspeed_nudge_cm;
|
|||
// 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel
|
||||
static int16_t throttle_nudge = 0;
|
||||
|
||||
// receiver RSSI
|
||||
static uint8_t receiver_rssi;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Ground speed
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -880,6 +884,8 @@ static void medium_loop()
|
|||
}
|
||||
#endif
|
||||
|
||||
read_receiver_rssi();
|
||||
|
||||
// Read altitude from sensors
|
||||
// ------------------
|
||||
update_alt();
|
||||
|
|
|
@ -301,7 +301,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||
0,
|
||||
0,
|
||||
0,
|
||||
receiver_rssi());
|
||||
receiver_rssi);
|
||||
}
|
||||
|
||||
static void NOINLINE send_radio_in(mavlink_channel_t chan)
|
||||
|
@ -318,7 +318,7 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
|
|||
g.rc_6.radio_in,
|
||||
g.rc_7.radio_in,
|
||||
g.rc_8.radio_in,
|
||||
receiver_rssi());
|
||||
receiver_rssi);
|
||||
}
|
||||
|
||||
static void NOINLINE send_radio_out(mavlink_channel_t chan)
|
||||
|
|
|
@ -56,17 +56,12 @@ static void read_battery(void)
|
|||
}
|
||||
|
||||
|
||||
// return receiver RSSI as an 8 bit number for MAVLink
|
||||
// read the receiver RSSI as an 8 bit number for MAVLink
|
||||
// RC_CHANNELS_SCALED message
|
||||
uint8_t receiver_rssi(void)
|
||||
void read_receiver_rssi(void)
|
||||
{
|
||||
#if RECEIVER_RSSI_PIN != -1
|
||||
float ret = RSSI_pin.read();
|
||||
if (ret >= 255) {
|
||||
return 255;
|
||||
}
|
||||
return (uint8_t)ret;
|
||||
#else
|
||||
return 0;
|
||||
receiver_rssi = constrain(ret, 0, 255);
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue