mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: use scaled throttle for accel-throttle's I term
Accel throttle's I term is taken from scaled manual throttle
This commit is contained in:
parent
e95f838cf6
commit
5a3c7b2d35
@ -1800,7 +1800,7 @@ bool set_throttle_mode( uint8_t new_throttle_mode )
|
|||||||
set_new_altitude(current_loc.alt); // by default hold the current altitude
|
set_new_altitude(current_loc.alt); // by default hold the current altitude
|
||||||
if ( throttle_mode <= THROTTLE_MANUAL_TILT_COMPENSATED ) { // 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();
|
reset_throttle_I();
|
||||||
set_accel_throttle_I_from_pilot_throttle();
|
set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in));
|
||||||
}
|
}
|
||||||
throttle_initialised = true;
|
throttle_initialised = true;
|
||||||
break;
|
break;
|
||||||
|
@ -1196,10 +1196,10 @@ static void reset_throttle_I(void)
|
|||||||
g.pid_throttle_accel.reset_I();
|
g.pid_throttle_accel.reset_I();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void set_accel_throttle_I_from_pilot_throttle(void)
|
static void set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle)
|
||||||
{
|
{
|
||||||
// shift difference between pilot's throttle and hover throttle into accelerometer I
|
// 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);
|
g.pid_throttle_accel.set_integrator(pilot_throttle-g.throttle_cruise);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reset_stability_I(void)
|
static void reset_stability_I(void)
|
||||||
|
Loading…
Reference in New Issue
Block a user