mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InertialNav: make use of ahrs library's get_accel_ef method to save some cpu cycles
This commit is contained in:
parent
1c08f176ea
commit
e9fa5dec0f
@ -65,7 +65,7 @@ void AP_InertialNav::update(float dt)
|
||||
|
||||
// convert accelerometer readings to earth frame
|
||||
Matrix3f dcm = _ahrs->get_dcm_matrix();
|
||||
accel_ef = dcm * _ins->get_accel();
|
||||
accel_ef = _ahrs->get_accel_ef();
|
||||
|
||||
// remove influence of gravity
|
||||
accel_ef.z += AP_INTERTIALNAV_GRAVITY;
|
||||
|
Loading…
Reference in New Issue
Block a user