From ac86c7999b0983dd430dfaeee647fef7ec2983a2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 8 Mar 2017 15:22:20 +0900 Subject: [PATCH] AP_GPS_MAV: set have_accuracy as boolean --- libraries/AP_GPS/AP_GPS_MAV.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index e49a26bc8e..cae9ad1191 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -90,17 +90,17 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg) if (have_sa) { state.speed_accuracy = packet.speed_accuracy; - state.have_speed_accuracy = 1; + state.have_speed_accuracy = true; } if (have_ha) { state.horizontal_accuracy = packet.horiz_accuracy; - state.have_horizontal_accuracy = 1; + state.have_horizontal_accuracy = true; } if (have_va) { state.vertical_accuracy = packet.vert_accuracy; - state.have_vertical_accuracy = 1; + state.have_vertical_accuracy = true; } state.num_sats = packet.satellites_visible; @@ -133,7 +133,7 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg) if (packet.cog < 36000) { state.ground_course = packet.cog / 100.0f; } - state.have_speed_accuracy = 0; + state.have_speed_accuracy = false; state.have_horizontal_accuracy = 0; state.have_vertical_accuracy = 0; if (packet.satellites_visible < 255) {