AP_ADSB: allow buffer to add to the max, instead of one less than the max

This commit is contained in:
Tom Pittenger 2016-06-14 20:40:08 -07:00
parent 0af8b42ade
commit ad81e56a64

View File

@ -242,7 +242,7 @@ void AP_ADSB::update_vehicle(const mavlink_message_t* packet)
// found, update it
set_vehicle(index, vehicle);
} else if (_vehicle_count < VEHICLE_LIST_LENGTH-1) {
} else if (_vehicle_count < VEHICLE_LIST_LENGTH) {
// not found and there's room, add it to the end of the list
set_vehicle(_vehicle_count, vehicle);