Browse Source

Sub: Disable optical flow by default

master
Jacob Walser 8 years ago committed by Andrew Tridgell
parent
commit
bb762092e8
  1. 2
      ArduSub/APM_Config.h
  2. 2
      ArduSub/config.h

2
ArduSub/APM_Config.h

@ -28,9 +28,9 @@ @@ -28,9 +28,9 @@
#define GRIPPER_ENABLED DISABLED // disable gripper to save 500bytes of flash
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
// features below are disabled by default on all boards
//#define OPTFLOW ENABLED // enable optical flow sensor support
//#define DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE // disable mode changes from GCS during Radio failsafes. Avoids a race condition for vehicle like Solo in which the RC and telemetry travel along the same link
// other settings

2
ArduSub/config.h

@ -268,7 +268,7 @@ @@ -268,7 +268,7 @@
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
#ifndef OPTFLOW
# define OPTFLOW ENABLED
# define OPTFLOW DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////

Loading…
Cancel
Save