diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 8a7f01b003..54fd36686a 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -80,8 +80,10 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg) if (have_vel_h) { Vector3f vel(packet.vn, packet.ve, 0); - if (have_vel_v) + if (have_vel_v) { vel.z = packet.vd; + state.have_vertical_velocity = true; + } state.velocity = vel; state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x)));