mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
added update throttle cruise function
This commit is contained in:
parent
414a2581a0
commit
24b760d48f
@ -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()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user