mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Beacon: fix comparison order to prevent using wrong beacon_instance first
This commit is contained in:
parent
4bccdada16
commit
0a922426a2
@ -214,7 +214,7 @@ bool AP_Beacon::beacon_healthy(uint8_t beacon_instance) const
|
|||||||
// return distance to beacon in meters
|
// return distance to beacon in meters
|
||||||
float AP_Beacon::beacon_distance(uint8_t beacon_instance) const
|
float AP_Beacon::beacon_distance(uint8_t beacon_instance) const
|
||||||
{
|
{
|
||||||
if (!beacon_state[beacon_instance].healthy || beacon_instance >= num_beacons) {
|
if ( beacon_instance >= num_beacons || !beacon_state[beacon_instance].healthy) {
|
||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
return beacon_state[beacon_instance].distance;
|
return beacon_state[beacon_instance].distance;
|
||||||
|
Loading…
Reference in New Issue
Block a user