mirror of https://github.com/ArduPilot/ardupilot
AP_RSSI: Use RC_Channels instead of hal.rcin
This commit is contained in:
parent
ddd32d3339
commit
70b1eb9836
|
@ -14,6 +14,7 @@
|
|||
*/
|
||||
|
||||
#include <AP_RSSI/AP_RSSI.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <utility>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
@ -129,7 +130,7 @@ float AP_RSSI::read_receiver_rssi()
|
|||
receiver_rssi = read_channel_rssi();
|
||||
break;
|
||||
case RssiType::RSSI_RECEIVER : {
|
||||
int16_t rssi = hal.rcin->get_rssi();
|
||||
int16_t rssi = RC_Channels::get_receiver_rssi();
|
||||
if (rssi != -1) {
|
||||
receiver_rssi = rssi / 255.0;
|
||||
}
|
||||
|
@ -165,7 +166,7 @@ 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 = hal.rcin->read(rssi_channel-1);
|
||||
uint16_t rssi_channel_value = RC_Channels::get_radio_in(rssi_channel-1);
|
||||
float channel_rssi = scale_and_constrain_float_rssi(rssi_channel_value, rssi_channel_low_pwm_value, rssi_channel_high_pwm_value);
|
||||
return channel_rssi;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue