Copter: enable optflow by default for Pixhawk

This commit is contained in:
Randy Mackay 2014-10-15 15:17:36 +09:00
parent 7b07b575cf
commit 67b7b2d667
2 changed files with 4 additions and 3 deletions

View File

@ -33,9 +33,9 @@
//#define EPM_ENABLED ENABLED // enable epm cargo gripper costs 500bytes of flash
//#define CLI_ENABLED ENABLED // enable the CLI (command-line-interface) at a cost of 21K of flash space
//#define NAV_GUIDED ENABLED // enable external navigation computer to control vehicle through MAV_CMD_NAV_GUIDED mission commands
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
// features below are disabled by default on all boards
//#define OPTFLOW ENABLED // enable optical flow sensor and OF_LOITER flight mode at a cost of 5K of flash space
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
// other settings

View File

@ -89,6 +89,7 @@
# define CLI_ENABLED DISABLED
# define FRSKY_TELEM_ENABLED DISABLED
# define NAV_GUIDED DISABLED
# define OPTFLOW DISABLED
#endif
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
@ -382,8 +383,8 @@
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW
#ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)
# define OPTFLOW DISABLED
#ifndef OPTFLOW
# define OPTFLOW ENABLED
#endif
// optical flow based loiter PI values
#ifndef OPTFLOW_ROLL_P