From c93c7af20cf844bdfd90854c2cad39a48bfbe318 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 8 Dec 2014 10:29:32 +0900 Subject: [PATCH] Copter: move update_optflow to sensors.pde No functional change --- ArduCopter/ArduCopter.pde | 30 ------------------------------ ArduCopter/sensors.pde | 30 ++++++++++++++++++++++++++++++ 2 files changed, 30 insertions(+), 30 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index db296b1d7d..a1e8a4a55c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1180,36 +1180,6 @@ static void one_hz_loop() #endif } -// called at 200hz -#if OPTFLOW == ENABLED -static void update_optical_flow(void) -{ - static uint32_t last_of_update = 0; - - // exit immediately if not enabled - if (!optflow.enabled()) { - return; - } - - // read from sensor - optflow.update(); - - // write to log and send to EKF if new data has arrived - if (optflow.last_update() != last_of_update) { - last_of_update = optflow.last_update(); - uint8_t flowQuality = optflow.quality(); - Vector2f flowRate = optflow.flowRate(); - Vector2f bodyRate = optflow.bodyRate(); - // Use range from a separate range finder if available, not the PX4Flows built in sensor which is ineffective - float ground_distance_m = 0.01f*float(sonar_alt); - ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, sonar_alt_health, ground_distance_m); - if (g.log_bitmask & MASK_LOG_OPTFLOW) { - Log_Write_Optflow(); - } - } -} -#endif // OPTFLOW == ENABLED - // called at 50hz static void update_GPS(void) { diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 2d5a5215be..c81968261e 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -109,6 +109,36 @@ static void init_optflow() #endif // OPTFLOW == ENABLED } +// called at 200hz +#if OPTFLOW == ENABLED +static void update_optical_flow(void) +{ + static uint32_t last_of_update = 0; + + // exit immediately if not enabled + if (!optflow.enabled()) { + return; + } + + // read from sensor + optflow.update(); + + // write to log and send to EKF if new data has arrived + if (optflow.last_update() != last_of_update) { + last_of_update = optflow.last_update(); + uint8_t flowQuality = optflow.quality(); + Vector2f flowRate = optflow.flowRate(); + Vector2f bodyRate = optflow.bodyRate(); + // Use range from a separate range finder if available, not the PX4Flows built in sensor which is ineffective + float ground_distance_m = 0.01f*float(sonar_alt); + ahrs.writeOptFlowMeas(flowQuality, flowRate, bodyRate, last_of_update, sonar_alt_health, ground_distance_m); + if (g.log_bitmask & MASK_LOG_OPTFLOW) { + Log_Write_Optflow(); + } + } +} +#endif // OPTFLOW == ENABLED + // read_battery - check battery voltage and current and invoke failsafe if necessary // called at 10hz static void read_battery(void)