ArduCopter: added ACCEL_ALT_HOLD and INERTIAL_NAV to config.h and commented out of APM_Config.h.
Reduces possibility of difference between arduino ide compiled code and script built code (i.e. autotester, mission planner)
This commit is contained in:
parent
1dd8606b17
commit
cdab521c7d
@ -46,9 +46,9 @@
|
||||
//#define TOY_EDF ENABLED
|
||||
//#define TOY_MIXER TOY_LOOKUP_TABLE
|
||||
|
||||
|
||||
#define ACCEL_ALT_HOLD 0 // disabled by default, work in progress
|
||||
#define INERTIAL_NAV DISABLED
|
||||
// Inertia based contollers. disabled by default, work in progress
|
||||
//#define ACCEL_ALT_HOLD 0
|
||||
//#define INERTIAL_NAV DISABLED
|
||||
|
||||
|
||||
#if INERTIAL_NAV == ENABLED
|
||||
@ -91,7 +91,7 @@
|
||||
|
||||
// to enable, set to 1
|
||||
// to disable, set to 0
|
||||
#define AUTO_THROTTLE_HOLD 1
|
||||
// #define AUTO_THROTTLE_HOLD 1
|
||||
|
||||
//#define LOGGING_ENABLED DISABLED
|
||||
|
||||
|
@ -1076,4 +1076,8 @@
|
||||
# define ALTERNATIVE_YAW_MODE DISABLED
|
||||
#endif
|
||||
|
||||
// Inertia based contollers. disabled by default, work in progress
|
||||
#define ACCEL_ALT_HOLD 0
|
||||
#define INERTIAL_NAV DISABLED
|
||||
|
||||
#endif // __ARDUCOPTER_CONFIG_H__
|
||||
|
Loading…
Reference in New Issue
Block a user