mirror of https://github.com/ArduPilot/ardupilot
trying to improve alt hold.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1608 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
dcccaf4ca7
commit
d373278068
|
@ -25,10 +25,14 @@ void calc_nav_throttle()
|
||||||
long error = constrain(altitude_error, -300, 300);
|
long error = constrain(altitude_error, -300, 300);
|
||||||
|
|
||||||
if(altitude_sensor == BARO) {
|
if(altitude_sensor == BARO) {
|
||||||
|
if(error > 0){
|
||||||
|
pid_baro_throttle.kP(.25);
|
||||||
|
}else{
|
||||||
|
pid_baro_throttle.kP(.05);
|
||||||
|
}
|
||||||
nav_throttle = pid_baro_throttle.get_pid(error, delta_ms_fast_loop, 1.0);
|
nav_throttle = pid_baro_throttle.get_pid(error, delta_ms_fast_loop, 1.0);
|
||||||
|
|
||||||
// limit output of throttle control
|
// limit output of throttle control
|
||||||
nav_throttle = throttle_cruise + constrain(nav_throttle, -50, 100);
|
nav_throttle = throttle_cruise + constrain(nav_throttle, -15, 70);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// SONAR
|
// SONAR
|
||||||
|
|
Loading…
Reference in New Issue