mirror of https://github.com/ArduPilot/ardupilot
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:
parent
f9892fac60
commit
211f964553
|
@ -446,8 +446,11 @@ get_throttle_rate(int16_t z_target_speed)
|
||||||
z_rate_error = z_target_speed - climb_rate; // calc the speed error
|
z_rate_error = z_target_speed - climb_rate; // calc the speed error
|
||||||
#endif
|
#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
|
// separately calculate p, i, d values for logging
|
||||||
p = g.pid_throttle.get_p(z_rate_error);
|
p = g.pid_throttle.get_p(z_rate_error);
|
||||||
|
@ -462,7 +465,7 @@ get_throttle_rate(int16_t z_target_speed)
|
||||||
|
|
||||||
//
|
//
|
||||||
// limit the rate
|
// 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
|
#if LOGGING_ENABLED == ENABLED
|
||||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||||
|
|
|
@ -902,6 +902,16 @@
|
||||||
# define THROTTLE_IMAX 300
|
# define THROTTLE_IMAX 300
|
||||||
#endif
|
#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
|
// Crosstrack compensation
|
||||||
|
|
Loading…
Reference in New Issue