mirror of https://github.com/ArduPilot/ardupilot
Copter: simplify APM_Config.h
Remove items that can be more easily set with parameters
This commit is contained in:
parent
28c37dd798
commit
19394918dd
|
@ -1,15 +1,14 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// Example config file. Take a look at config.h. Any term define there can be
|
||||
// overridden by defining it here.
|
||||
|
||||
// User specific config file. Any items listed in config.h can be overridden here.
|
||||
|
||||
// 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.
|
||||
|
||||
//#define HIL_MODE HIL_MODE_SENSORS
|
||||
//#define DMP_ENABLED ENABLED
|
||||
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes
|
||||
//#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation
|
||||
//#define LOGGING_ENABLED DISABLED // disable logging to save code space
|
||||
//#define DMP_ENABLED ENABLED // use MPU6000's DMP instead of DCM for attitude estimation
|
||||
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes
|
||||
|
||||
//#define FRAME_CONFIG QUAD_FRAME
|
||||
/*
|
||||
|
@ -23,42 +22,16 @@
|
|||
* HELI_FRAME
|
||||
*/
|
||||
|
||||
//#define FRAME_ORIENTATION X_FRAME
|
||||
/*
|
||||
* PLUS_FRAME
|
||||
* X_FRAME
|
||||
* V_FRAME
|
||||
*/
|
||||
|
||||
//#define CH7_OPTION CH7_SAVE_WP
|
||||
/*
|
||||
* CH7_DO_NOTHING
|
||||
* CH7_FLIP
|
||||
* CH7_SIMPLE_MODE
|
||||
* CH7_RTL
|
||||
* CH7_SAVE_TRIM
|
||||
* CH7_SAVE_WP
|
||||
* CH7_CAMERA_TRIGGER
|
||||
*/
|
||||
|
||||
// uncomment the line below to disable control of yaw during missions (or set YAW_BEHAVIOR parameter to 0)
|
||||
// #define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_NONE
|
||||
|
||||
//#define MOTORS_JD880
|
||||
//#define MOTORS_JD850
|
||||
|
||||
|
||||
// the choice of function names is up to the user and does not have to match these
|
||||
// uncomment these hooks and ensure there is a matching function on your "UserCode.pde" file
|
||||
//#define USERHOOK_FASTLOOP userhook_FastLoop();
|
||||
#define USERHOOK_50HZLOOP userhook_50Hz();
|
||||
//#define USERHOOK_MEDIUMLOOP userhook_MediumLoop();
|
||||
//#define USERHOOK_SLOWLOOP userhook_SlowLoop();
|
||||
//#define USERHOOK_SUPERSLOWLOOP userhook_SuperSlowLoop();
|
||||
#define USERHOOK_INIT userhook_init();
|
||||
|
||||
// the choice of included variables file (*.h) is up to the user and does not have to match this one
|
||||
// Ensure the defined file exists and is in the arducopter directory
|
||||
// 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).
|
||||
#define USERHOOK_VARIABLES "UserVariables.h"
|
||||
|
||||
//#define LOGGING_ENABLED DISABLED
|
||||
// Put your custom code into the UserCode.pde with function names matching those listed below and ensure the appropriate #define below is uncommented below
|
||||
#define USERHOOK_INIT userhook_init(); // for code to be run once at startup
|
||||
//#define USERHOOK_FASTLOOP userhook_FastLoop(); // for code to be run at 100hz
|
||||
#define USERHOOK_50HZLOOP userhook_50Hz(); // for code to be run at 50hz
|
||||
//#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
|
||||
|
|
|
@ -1019,6 +1019,7 @@ static void fast_loop()
|
|||
#endif
|
||||
}
|
||||
|
||||
// medium_loop - runs at 10hz
|
||||
static void medium_loop()
|
||||
{
|
||||
// This is the start of the medium (10 Hz) loop pieces
|
||||
|
|
Loading…
Reference in New Issue