AP_ADSB: compiler warning: init value before use even though it already is

silly compiler warnings.. this one is incorrect but it throws a conservative warning which this solves
This commit is contained in:
Tom Pittenger 2016-07-25 10:14:00 -07:00
parent dce734d196
commit 2c6340bb10

View File

@ -381,7 +381,7 @@ void AP_ADSB::update_vehicle(const mavlink_message_t* packet)
return;
}
uint16_t index;
uint16_t index = in_state.list_size + 1; // initialize with invalid index
adsb_vehicle_t vehicle {};
mavlink_msg_adsb_vehicle_decode(packet, &vehicle.info);
Location_Class vehicle_loc = Location_Class(AP_ADSB::get_location(vehicle));