AP_RSSI: use rc() method to get rc singleton

This commit is contained in:
Peter Barker 2018-04-26 22:00:09 +10:00 committed by Randy Mackay
parent 2489234fcf
commit 497746c3d0
1 changed files with 5 additions and 1 deletions

View File

@ -186,7 +186,11 @@ float AP_RSSI::read_pin_rssi()
// read the RSSI value from a PWM value on a RC channel
float AP_RSSI::read_channel_rssi()
{
uint16_t rssi_channel_value = RC_Channels::get_radio_in(rssi_channel-1);
RC_Channel *ch = rc().channel(rssi_channel-1);
if (ch == nullptr) {
return 0.0f;
}
uint16_t rssi_channel_value = ch->get_radio_in();
float channel_rssi = scale_and_constrain_float_rssi(rssi_channel_value, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
return channel_rssi;
}