mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
DCM: fixed an uninitialised variable warning
This commit is contained in:
parent
7d9c4094a2
commit
a60cf111c5
@ -367,7 +367,7 @@ AP_DCM::drift_correction(void)
|
|||||||
float integrator_magnitude;
|
float integrator_magnitude;
|
||||||
Vector3f accel;
|
Vector3f accel;
|
||||||
Vector3f error;
|
Vector3f error;
|
||||||
float error_norm;
|
float error_norm = 0;
|
||||||
const float gravity_squared = (9.80665*9.80665);
|
const float gravity_squared = (9.80665*9.80665);
|
||||||
|
|
||||||
accel = _accel_vector;
|
accel = _accel_vector;
|
||||||
|
Loading…
Reference in New Issue
Block a user