2011-09-17 15:25:31 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2013-05-17 00:01:39 -03:00
// User specific config file. Any items listed in config.h can be overridden here.
2012-09-05 19:36:57 -03:00
2012-12-13 19:27:42 -04:00
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.
2012-01-08 21:59:55 -04:00
2012-11-26 22:50:39 -04:00
//#define FRAME_CONFIG QUAD_FRAME
2014-02-06 08:28:55 -04:00
/* options:
2012-08-21 23:19:50 -03:00
* QUAD_FRAME
* TRI_FRAME
* HEXA_FRAME
* Y6_FRAME
* OCTA_FRAME
* OCTA_QUAD_FRAME
* HELI_FRAME
2013-10-02 06:59:04 -03:00
* SINGLE_FRAME
2014-02-06 08:28:55 -04:00
* COAX_FRAME
2012-08-21 23:19:50 -03:00
*/
2011-05-14 23:03:23 -03:00
2013-10-28 00:36:52 -03:00
// uncomment the lines below to save on flash space if compiling for the APM using Arduino IDE. Top items save the most flash space
2014-03-08 02:15:21 -04:00
# if (CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_APM1)
# define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
# endif
2013-09-26 01:15:30 -03:00
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
2014-02-02 03:59:17 -04:00
//#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash
2013-10-28 00:36:52 -03:00
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
2014-04-23 03:24:03 -03:00
//#define HYBRID_ENABLED DISABLED // disable hybrid flight mode to save 4.5k of flash
2013-10-28 00:36:52 -03:00
2014-05-27 02:43:33 -03:00
// features below are disabled by default on APM (but enabled on Pixhawk)
2014-04-30 09:26:29 -03:00
//#define AC_RALLY ENABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
2014-05-27 02:43:33 -03:00
//#define PARACHUTE ENABLED // enable parachute release at a cost of 1k of flash
// 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
2013-10-28 00:36:52 -03:00
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
2013-12-17 02:31:43 -04:00
//#define EPM_ENABLED ENABLED // enable epm cargo gripper costs 500bytes of flash
2013-09-26 01:15:30 -03:00
2014-01-14 22:31:00 -04:00
// other settings
//#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000)
//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // when set to DISABLED vehicle will disarm after landing (in LAND mode or RTL) even if pilot has not put throttle to zero
2013-10-13 08:41:11 -03:00
2013-09-26 01:15:30 -03:00
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
2013-05-17 00:01:39 -03:00
// User Hooks : For User Developed code that you wish to run
// Put your variable definitions into the UserVariables.h file (or another file name and then change the #define below).
2013-05-17 00:19:07 -03:00
//#define USERHOOK_VARIABLES "UserVariables.h"
2013-05-17 00:01:39 -03:00
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
2013-05-17 00:19:07 -03:00
//#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
2013-05-17 00:01:39 -03:00
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
2013-05-17 00:19:07 -03:00
//#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
2013-05-17 00:01:39 -03:00
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop(); // for code to be run at 10hz
//#define USERHOOK_SLOWLOOP userhook_SlowLoop(); // for code to be run at 3.3hz
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop(); // for code to be run at 1hz