mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
added error limit to alt hold
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1599 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
d1e9d62072
commit
20a57b8932
@ -20,16 +20,19 @@ void output_auto_throttle()
|
||||
}
|
||||
|
||||
void calc_nav_throttle()
|
||||
{
|
||||
{
|
||||
// limit error
|
||||
long error = constrain(altitude_error, -300, 300);
|
||||
|
||||
if(altitude_sensor == BARO) {
|
||||
nav_throttle = pid_baro_throttle.get_pid(altitude_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
|
||||
nav_throttle = throttle_cruise + constrain(nav_throttle, -50, 100);
|
||||
|
||||
} else {
|
||||
// SONAR
|
||||
nav_throttle = pid_sonar_throttle.get_pid(altitude_error, delta_ms_fast_loop, 1.0);
|
||||
nav_throttle = pid_sonar_throttle.get_pid(error, delta_ms_fast_loop, 1.0);
|
||||
|
||||
// limit output of throttle control
|
||||
nav_throttle = throttle_cruise + constrain(nav_throttle, -60, 100);
|
||||
|
Loading…
Reference in New Issue
Block a user