added update throttle cruise function

This commit is contained in:
Jason Short 2012-01-13 16:48:05 -08:00
parent 1269b07d9a
commit 7877a872d3
1 changed files with 11 additions and 3 deletions

View File

@ -558,9 +558,7 @@ static void set_mode(byte mode)
if(throttle_mode == THROTTLE_MANUAL){
// reset all of the throttle iterms
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();
update_throttle_cruise();
}else {
// an automatic throttle
// todo: replace with a throttle cruise estimator
@ -605,6 +603,16 @@ init_simple_bearing()
initial_simple_bearing = dcm.yaw_sensor;
}
static void update_throttle_cruise()
{
int16_t tmp = g.pi_alt_hold.get_integrator();
if(tmp != 0){
g.throttle_cruise += tmp;
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();
}
}
static void
init_throttle_cruise()
{