renamed err to altitude_error

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1478 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-01-10 02:49:45 +00:00
parent cfea6b014a
commit bcd3e7db56
1 changed files with 2 additions and 2 deletions

View File

@ -24,13 +24,13 @@ void calc_nav_throttle()
long t_out;
if(altitude_sensor == BARO) {
t_out = pid_baro_throttle.get_pid(err, deltaMiliSeconds, 1.0);
t_out = pid_baro_throttle.get_pid(altitude_error, deltaMiliSeconds, 1.0);
// limit output of throttle control
t_out = throttle_cruise + constrain(t_out, -50, 100);
} else {
// SONAR
t_out = pid_sonar_throttle.get_pid(err, deltaMiliSeconds, 1.0);
t_out = pid_sonar_throttle.get_pid(altitude_error, deltaMiliSeconds, 1.0);
// limit output of throttle control
t_out = throttle_cruise + constrain(t_out, -60, 100);