Alt Hold updates

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2405 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-26 19:57:19 +00:00
parent 8088f24427
commit eda421e8ea
3 changed files with 9 additions and 9 deletions

View File

@ -137,7 +137,7 @@ void calc_nav_throttle()
if(altitude_sensor == BARO){
nav_throttle = g.pid_baro_throttle.get_pid(error, dTnav2, scaler); // .25
nav_throttle = g.throttle_cruise + constrain(nav_throttle, -70, 140);
nav_throttle = g.throttle_cruise + constrain(nav_throttle, -35, 80);
}else{
nav_throttle = g.pid_sonar_throttle.get_pid(error, dTnav2, scaler); // .5
nav_throttle = g.throttle_cruise + constrain(nav_throttle, -70, 150);

View File

@ -424,27 +424,27 @@
// Throttle control gains
//
#ifndef THROTTLE_BARO_P
# define THROTTLE_BARO_P 0.25
# define THROTTLE_BARO_P 0.2 // trying a lower val
#endif
#ifndef THROTTLE_BARO_I
# define THROTTLE_BARO_I 0.01 //with 4m error, 12.5s windup
# define THROTTLE_BARO_I 0.02 //with 4m error, 12.5s windup
#endif
#ifndef THROTTLE_BARO_D
# define THROTTLE_BARO_D 0.03
# define THROTTLE_BARO_D 0.06 //
#endif
#ifndef THROTTLE_BARO_IMAX
# define THROTTLE_BARO_IMAX 50
# define THROTTLE_BARO_IMAX 20
#endif
#ifndef THROTTLE_SONAR_P
# define THROTTLE_SONAR_P 0.8 // upped from .5
# define THROTTLE_SONAR_P 0.5 //
#endif
#ifndef THROTTLE_SONAR_I
# define THROTTLE_SONAR_I 0.01
# define THROTTLE_SONAR_I 0.1
#endif
#ifndef THROTTLE_SONAR_D
# define THROTTLE_SONAR_D 0.05
# define THROTTLE_SONAR_D 0.06
#endif
#ifndef THROTTLE_SONAR_IMAX
# define THROTTLE_SONAR_IMAX 60

View File

@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
};
// Create the top-level menu object.
MENU(main_menu, "AC 2.0.13 Beta", main_menu_commands);
MENU(main_menu, "AC 2.0.14 Beta", main_menu_commands);
void init_ardupilot()
{