AP_TECS: use ins singleton
This commit is contained in:
parent
e2de9d62cd
commit
f0daf392a5
@ -325,7 +325,7 @@ void AP_TECS::update_50hz(void)
|
|||||||
// Get DCM
|
// Get DCM
|
||||||
const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
|
const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
|
||||||
// Calculate speed rate of change
|
// Calculate speed rate of change
|
||||||
float temp = rotMat.c.x * GRAVITY_MSS + _ahrs.get_ins().get_accel().x;
|
float temp = rotMat.c.x * GRAVITY_MSS + AP::ins().get_accel().x;
|
||||||
// take 5 point moving average
|
// take 5 point moving average
|
||||||
_vel_dot = _vdot_filter.apply(temp);
|
_vel_dot = _vdot_filter.apply(temp);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user