Skip to content
Snippets Groups Projects
Commit 24b760d4 authored by Jason Short's avatar Jason Short
Browse files

added update throttle cruise function

parent 414a2581
No related branches found
No related tags found
No related merge requests found
...@@ -558,9 +558,7 @@ static void set_mode(byte mode) ...@@ -558,9 +558,7 @@ static void set_mode(byte mode)
if(throttle_mode == THROTTLE_MANUAL){ if(throttle_mode == THROTTLE_MANUAL){
// reset all of the throttle iterms // reset all of the throttle iterms
g.pi_alt_hold.reset_I(); update_throttle_cruise();
g.pi_throttle.reset_I();
}else { }else {
// an automatic throttle // an automatic throttle
// todo: replace with a throttle cruise estimator // todo: replace with a throttle cruise estimator
...@@ -605,6 +603,16 @@ init_simple_bearing() ...@@ -605,6 +603,16 @@ init_simple_bearing()
initial_simple_bearing = dcm.yaw_sensor; 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 static void
init_throttle_cruise() init_throttle_cruise()
{ {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment