ArduCopter: smooth throttle when switching from manual throttle to alt hold

new set_accel_throttle_I_from_pilot_throttle function copies the
difference between the pilot's throttle and hover throttle to the
accelerometer based throttle controller's I term.
This commit is contained in:
Randy Mackay 2013-01-12 12:20:37 +09:00
parent cad9533398
commit a18892229c
2 changed files with 8 additions and 2 deletions

View File

@ -1798,8 +1798,9 @@ bool set_throttle_mode( uint8_t new_throttle_mode )
case THROTTLE_AUTO:
controller_desired_alt = current_loc.alt; // reset controller desired altitude to current altitude
set_new_altitude(current_loc.alt); // by default hold the current altitude
if ( throttle_mode < THROTTLE_HOLD ) { // reset the alt hold I terms if previous throttle mode was manual
if ( throttle_mode <= THROTTLE_MANUAL_TILT_COMPENSATED ) { // reset the alt hold I terms if previous throttle mode was manual
reset_throttle_I();
set_accel_throttle_I_from_pilot_throttle();
}
throttle_initialised = true;
break;

View File

@ -1069,7 +1069,6 @@ get_throttle_land()
set_land_complete(true);
if( g.rc_3.control_in == 0 || ap.failsafe ) {
init_disarm_motors();
reset_throttle_I();
}
}
}else{
@ -1166,6 +1165,12 @@ static void reset_throttle_I(void)
g.pid_throttle_accel.reset_I();
}
static void set_accel_throttle_I_from_pilot_throttle(void)
{
// shift difference between pilot's throttle and hover throttle into accelerometer I
g.pid_throttle_accel.set_integrator(g.rc_3.control_in-g.throttle_cruise);
}
static void reset_stability_I(void)
{
// Used to balance a quad