mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: make use of ahrs library's get_accel_ef method to save some cpu cycles
This commit is contained in:
parent
2b6fbe5c01
commit
50bd21d548
|
@ -69,7 +69,7 @@ void AP_InertialNav::update(float dt)
|
||||||
|
|
||||||
// convert accelerometer readings to earth frame
|
// convert accelerometer readings to earth frame
|
||||||
Matrix3f dcm = _ahrs->get_dcm_matrix();
|
Matrix3f dcm = _ahrs->get_dcm_matrix();
|
||||||
accel_ef = dcm * _ins->get_accel();
|
accel_ef = _ahrs->get_accel_ef();
|
||||||
|
|
||||||
// remove influence of gravity
|
// remove influence of gravity
|
||||||
accel_ef.z += AP_INTERTIALNAV_GRAVITY;
|
accel_ef.z += AP_INTERTIALNAV_GRAVITY;
|
||||||
|
|
Loading…
Reference in New Issue