Arducopter: Config.h defaults adjustments

This commit is contained in:
Jason Short 2012-07-19 17:48:48 -07:00
parent 219fed1441
commit f7017f1fb3
1 changed files with 8 additions and 8 deletions

View File

@ -430,7 +430,7 @@
#endif #endif
#ifndef AUTO_LAND_TIME #ifndef AUTO_LAND_TIME
# define AUTO_LAND_TIME 10 # define AUTO_LAND_TIME 5
#endif #endif
@ -565,7 +565,11 @@
// RTL Mode // RTL Mode
#ifndef RTL_APPROACH_ALT #ifndef RTL_APPROACH_ALT
# define RTL_APPROACH_ALT 200 # define RTL_APPROACH_ALT 200 // cm!!!
#endif
#ifndef RTL_HOLD_ALT
# define RTL_HOLD_ALT 1500 // height to return to Home in CM, 0 = Maintain current altitude
#endif #endif
@ -786,10 +790,10 @@
// RATE control // RATE control
#ifndef THROTTLE_P #ifndef THROTTLE_P
# define THROTTLE_P 0.4 // .25 # define THROTTLE_P 0.3 // .25
#endif #endif
#ifndef THROTTLE_I #ifndef THROTTLE_I
# define THROTTLE_I 0.02 # define THROTTLE_I 0.03
#endif #endif
#ifndef THROTTLE_D #ifndef THROTTLE_D
# define THROTTLE_D 0.0 // # define THROTTLE_D 0.0 //
@ -943,10 +947,6 @@
# define LOITER_RADIUS 10 // meters for circle mode # define LOITER_RADIUS 10 // meters for circle mode
#endif #endif
#ifndef ALT_HOLD_HOME
# define ALT_HOLD_HOME 0 // height to return to Home in CM, 0 = Maintain current altitude
#endif
#ifndef USE_CURRENT_ALT #ifndef USE_CURRENT_ALT
# define USE_CURRENT_ALT FALSE # define USE_CURRENT_ALT FALSE
#endif #endif