mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Beacon: fix potential out-of-bounds write to beacon_state
uncovered by covarity and wickedshell
This commit is contained in:
parent
d4d35bdcbd
commit
9fc0bc19e7
@ -38,7 +38,7 @@ void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy
|
|||||||
void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
|
void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
|
||||||
{
|
{
|
||||||
// sanity check instance
|
// sanity check instance
|
||||||
if (beacon_instance > AP_BEACON_MAX_BEACONS) {
|
if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -57,7 +57,7 @@ void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float dista
|
|||||||
void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
|
void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
|
||||||
{
|
{
|
||||||
// sanity check instance
|
// sanity check instance
|
||||||
if (beacon_instance > AP_BEACON_MAX_BEACONS) {
|
if (beacon_instance >= AP_BEACON_MAX_BEACONS) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user