AP_OpticalFlow: cope if AP_AHRS_ENABLED is 0

This commit is contained in:
Peter Barker 2023-07-12 16:23:58 +10:00 committed by Peter Barker
parent 1e41030167
commit f4d51fd8f5
2 changed files with 6 additions and 0 deletions

View File

@ -267,6 +267,7 @@ void AP_OpticalFlow::update_state(const OpticalFlow_state &state)
_state = state; _state = state;
_last_update_ms = AP_HAL::millis(); _last_update_ms = AP_HAL::millis();
#if AP_AHRS_ENABLED
// write to log and send to EKF if new data has arrived // write to log and send to EKF if new data has arrived
AP::ahrs().writeOptFlowMeas(quality(), AP::ahrs().writeOptFlowMeas(quality(),
_state.flowRate, _state.flowRate,
@ -274,6 +275,7 @@ void AP_OpticalFlow::update_state(const OpticalFlow_state &state)
_last_update_ms, _last_update_ms,
get_pos_offset(), get_pos_offset(),
get_height_override()); get_height_override());
#endif
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED
Log_Write_Optflow(); Log_Write_Optflow();
#endif #endif

View File

@ -287,7 +287,11 @@ void AP_OpticalFlow_Pixart::timer(void)
uint32_t dt_us = last_burst_us - integral.last_frame_us; uint32_t dt_us = last_burst_us - integral.last_frame_us;
float dt = dt_us * 1.0e-6; float dt = dt_us * 1.0e-6;
#if AP_AHRS_ENABLED
const Vector3f &gyro = AP::ahrs().get_gyro(); const Vector3f &gyro = AP::ahrs().get_gyro();
#else
const Vector3f &gyro = AP::ins().get_gyro();
#endif
{ {
WITH_SEMAPHORE(_sem); WITH_SEMAPHORE(_sem);