mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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
This commit is contained in:
parent
42cca17df4
commit
38b3d3ff3a
@ -59,7 +59,7 @@ void AP_GPS_MAV::handle_msg(mavlink_message_t *msg)
|
|||||||
state.time_week_ms = packet.time_week_ms;
|
state.time_week_ms = packet.time_week_ms;
|
||||||
state.status = (AP_GPS::GPS_Status)packet.fix_type;
|
state.status = (AP_GPS::GPS_Status)packet.fix_type;
|
||||||
|
|
||||||
Location loc;
|
Location loc = {};
|
||||||
loc.lat = packet.lat;
|
loc.lat = packet.lat;
|
||||||
loc.lng = packet.lon;
|
loc.lng = packet.lon;
|
||||||
if (have_alt) {
|
if (have_alt) {
|
||||||
|
Loading…
Reference in New Issue
Block a user