mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Plane: pass pitch trim parameter to TECS
This commit is contained in:
parent
8851a92dfd
commit
60b5c9fd38
@ -603,7 +603,8 @@ void Plane::update_alt()
|
||||
get_takeoff_pitch_min_cd(),
|
||||
throttle_nudge,
|
||||
tecs_hgt_afe(),
|
||||
aerodynamic_load_factor);
|
||||
aerodynamic_load_factor,
|
||||
g.pitch_trim.get());
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user