From 38b3d3ff3ab707db27ece0c04ae0c8dd38fe6073 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 1 Sep 2016 12:01:14 +0900 Subject: [PATCH] AP_GPS_MAV: initialise location while handling_msg This reduces a covarity warning but it likely not really an issue because we always initialise newly allocated memory to zero anyway --- libraries/AP_GPS/AP_GPS_MAV.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index b1970170ca..11ec17ff3d 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -59,7 +59,7 @@ void AP_GPS_MAV::handle_msg(mavlink_message_t *msg) state.time_week_ms = packet.time_week_ms; state.status = (AP_GPS::GPS_Status)packet.fix_type; - Location loc; + Location loc = {}; loc.lat = packet.lat; loc.lng = packet.lon; if (have_alt) {