ArduCopter: allow tuning of the Throttle Rate D term

This commit is contained in:
rmackay9 2012-12-15 13:06:24 +09:00 committed by Andrew Tridgell
parent f778961acf
commit f4c50353b9
2 changed files with 2 additions and 1 deletions

View File

@ -968,7 +968,7 @@ get_throttle_rate(int16_t z_target_speed)
#if LOGGING_ENABLED == ENABLED
static uint8_t log_counter = 0; // used to slow down logging of PID values to dataflash
// log output if PID loggins is on and we are tuning the yaw
if( g.log_bitmask & MASK_LOG_PID && g.radio_tuning == CH6_THROTTLE_KP ) {
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_THROTTLE_KP || g.radio_tuning == CH6_THROTTLE_KI || g.radio_tuning == CH6_THROTTLE_KD) ) {
log_counter++;
if( log_counter >= 10 ) { // (update rate / desired output rate) = (50hz / 10hz) = 5hz
log_counter = 0;

View File

@ -153,6 +153,7 @@
#define CH6_THR_HOLD_KP 14 // altitude hold controller's P term (alt error to desired rate)
#define CH6_THROTTLE_KP 7 // throttle rate controller's P term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_KI 33 // throttle rate controller's I term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_KD 37 // throttle rate controller's D term (desired rate to acceleration or motor output)
#define CH6_THR_ACCEL_KP 34 // accel based throttle controller's P term
#define CH6_THR_ACCEL_KI 35 // accel based throttle controller's I term
#define CH6_THR_ACCEL_KD 36 // accel based throttle controller's D term