mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
AP_RSSI: handle init ordering with MSP
this fixes a nullptr dereference on startup when MSP asks for RSSI data before the RSSI library is initialised Fixes #15824
This commit is contained in:
parent
248ef92ed7
commit
5385f25868
@ -167,6 +167,9 @@ uint8_t AP_RSSI::read_receiver_rssi_uint8()
|
||||
// read the RSSI value from an analog pin - returns float in range 0.0 to 1.0
|
||||
float AP_RSSI::read_pin_rssi()
|
||||
{
|
||||
if (!rssi_analog_source) {
|
||||
return 0;
|
||||
}
|
||||
rssi_analog_source->set_pin(rssi_analog_pin);
|
||||
float current_analog_voltage = rssi_analog_source->voltage_average();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user