AP_AHRS_NavEKF: Push gyro bias for optical flow
Push gyro bias for optical flow usage only if there is an optical flow declared in the HAL
This commit is contained in:
parent
3d9dacb227
commit
d2afa1cac8
@ -90,6 +90,12 @@ void AP_AHRS_NavEKF::update(void)
|
||||
|
||||
// call AHRS_update hook if any
|
||||
AP_Module::call_hook_AHRS_update(*this);
|
||||
|
||||
// push gyros if optical flow present
|
||||
if (hal.opticalflow) {
|
||||
Vector3f exported_gyro_bias = get_gyro_drift();
|
||||
hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);
|
||||
}
|
||||
}
|
||||
|
||||
void AP_AHRS_NavEKF::update_DCM(void)
|
||||
|
Loading…
Reference in New Issue
Block a user