mirror of https://github.com/ArduPilot/ardupilot
Plane: pass pitch trim parameter to TECS
This commit is contained in:
parent
eadf5596ed
commit
bd928fb044
|
@ -597,7 +597,8 @@ void Plane::update_alt()
|
||||||
get_takeoff_pitch_min_cd(),
|
get_takeoff_pitch_min_cd(),
|
||||||
throttle_nudge,
|
throttle_nudge,
|
||||||
tecs_hgt_afe(),
|
tecs_hgt_afe(),
|
||||||
aerodynamic_load_factor);
|
aerodynamic_load_factor,
|
||||||
|
g.pitch_trim.get());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue