Changes to get_throttle_rate()

Commented out a bit of code that is not used currently
Change the output constrains to #defines so they can be easily changed, particularly for use in TradHeli.
This commit is contained in:
Robert Lefebvre 2012-11-21 17:11:38 -05:00
parent f9892fac60
commit 211f964553
2 changed files with 16 additions and 3 deletions

View File

@ -446,8 +446,11 @@ get_throttle_rate(int16_t z_target_speed)
z_rate_error = z_target_speed - climb_rate; // calc the speed error
#endif
int16_t tmp = ((int32_t)z_target_speed * (int32_t)g.throttle_cruise) / 280;
tmp = min(tmp, 500);
////////////////////////////////////////////////////////////////////////////////////////
// Commenting this out because 'tmp' is not being used anymore?
// Robert Lefebvre 21/11/2012
// int16_t tmp = ((int32_t)z_target_speed * (int32_t)g.throttle_cruise) / 280;
// tmp = min(tmp, 500);
// separately calculate p, i, d values for logging
p = g.pid_throttle.get_p(z_rate_error);
@ -462,7 +465,7 @@ get_throttle_rate(int16_t z_target_speed)
//
// limit the rate
output += constrain(p+i+d, -150, 200);
output += constrain(p+i+d, THROTTLE_RATE_CONSTRAIN_NEGATIVE, THROTTLE_RATE_CONSTRAIN_POSITIVE);
#if LOGGING_ENABLED == ENABLED
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash

View File

@ -902,6 +902,16 @@
# define THROTTLE_IMAX 300
#endif
#ifndef THROTTLE_RATE_CONSTRAIN_POSITIVE
# define THROTTLE_RATE_CONSTRAIN_POSITIVE 200
#endif
#ifndef THROTTLE_RATE_CONSTRAIN_NEGATIVE
# define THROTTLE_RATE_CONSTRAIN_NEGATIVE -150
#endif
//////////////////////////////////////////////////////////////////////////////
// Crosstrack compensation