From 43a53aa303617f8dd5761acd4b1e36560d942e28 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 9 Dec 2011 18:42:15 +1100 Subject: [PATCH] dcm: fixed an uninitialised variable if no compass and not in motion the DCM we would multiply by an uninitialised number --- libraries/AP_DCM/AP_DCM.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DCM/AP_DCM.cpp b/libraries/AP_DCM/AP_DCM.cpp index 5d813d793c..e913adfe1c 100644 --- a/libraries/AP_DCM/AP_DCM.cpp +++ b/libraries/AP_DCM/AP_DCM.cpp @@ -264,7 +264,7 @@ AP_DCM::drift_correction(void) //Compensation the Roll, Pitch and Yaw drift. //float mag_heading_x; //float mag_heading_y; - float error_course; + float error_course = 0; float accel_magnitude; float accel_weight; float integrator_magnitude;