mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
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:
parent
81c44ffec7
commit
0a07b25e39
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user