From af77425636ff63534864482821435211aed73bc7 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Tue, 11 Dec 2012 00:09:45 +0900 Subject: [PATCH] ArduCopter: fix Failed to Init Optflow message at startup --- ArduCopter/Attitude.pde | 4 ++-- ArduCopter/Parameters.pde | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 6ff75bb87f..a49a967be0 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -589,7 +589,7 @@ get_rate_yaw(int32_t target_rate) static int32_t get_of_roll(int32_t input_roll) { -#ifdef OPTFLOW_ENABLED +#if OPTFLOW == ENABLED static float tot_x_cm = 0; // total distance from target static uint32_t last_of_roll_update = 0; int32_t new_roll = 0; @@ -643,7 +643,7 @@ get_of_roll(int32_t input_roll) static int32_t get_of_pitch(int32_t input_pitch) { -#ifdef OPTFLOW_ENABLED +#if OPTFLOW == ENABLED static float tot_y_cm = 0; // total distance from target static uint32_t last_of_pitch_update = 0; int32_t new_pitch = 0; diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 1bcc1bbeea..a343b10e55 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -122,7 +122,7 @@ const AP_Param::Info var_info[] PROGMEM = { // @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow // @Values: 0:Disabled,1:Enabled // @User: Standard - GSCALAR(optflow_enabled, "FLOW_ENABLE", OPTFLOW), + GSCALAR(optflow_enabled, "FLOW_ENABLE", DISABLED), // @Param: LOW_VOLT // @DisplayName: Low Voltage