mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: fixed throttle nudge
broken by recent radio input changes Thanks to Michael for noticing!
This commit is contained in:
parent
e9fc158c8a
commit
a278a152fc
@ -200,8 +200,8 @@ void Plane::read_radio()
|
|||||||
|
|
||||||
control_failsafe();
|
control_failsafe();
|
||||||
|
|
||||||
if (g.throttle_nudge && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) > 50 && geofence_stickmixing()) {
|
if (g.throttle_nudge && channel_throttle->get_control_in() > 50 && geofence_stickmixing()) {
|
||||||
float nudge = (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) - 50) * 0.02f;
|
float nudge = (channel_throttle->get_control_in() - 50) * 0.02f;
|
||||||
if (ahrs.airspeed_sensor_enabled()) {
|
if (ahrs.airspeed_sensor_enabled()) {
|
||||||
airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.airspeed_cruise_cm) * nudge;
|
airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.airspeed_cruise_cm) * nudge;
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user