mirror of https://github.com/ArduPilot/ardupilot
dcm: fixed an uninitialised variable
if no compass and not in motion the DCM we would multiply by an uninitialised number
This commit is contained in:
parent
bb861117a3
commit
43a53aa303
|
@ -264,7 +264,7 @@ AP_DCM::drift_correction(void)
|
||||||
//Compensation the Roll, Pitch and Yaw drift.
|
//Compensation the Roll, Pitch and Yaw drift.
|
||||||
//float mag_heading_x;
|
//float mag_heading_x;
|
||||||
//float mag_heading_y;
|
//float mag_heading_y;
|
||||||
float error_course;
|
float error_course = 0;
|
||||||
float accel_magnitude;
|
float accel_magnitude;
|
||||||
float accel_weight;
|
float accel_weight;
|
||||||
float integrator_magnitude;
|
float integrator_magnitude;
|
||||||
|
|
Loading…
Reference in New Issue