mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
ArduCopter: fix Failed to Init Optflow message at startup
This commit is contained in:
parent
770e1b97f2
commit
628fb1da15
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user