Skip to content

Commit

Permalink
Plane: output nav scripting throttle with rest of nav scripting stuff
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Feb 6, 2024
1 parent 2729b11 commit 03ff3b1
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 7 deletions.
1 change: 1 addition & 0 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,6 +420,7 @@ void Plane::stabilize()
}
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);
#endif
} else {
plane.control_mode->run();
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,6 @@ void ModeAuto::update()
// NAV_SCRIPTING has a desired roll and pitch rate and desired throttle
plane.nav_roll_cd = ahrs.roll_sensor;
plane.nav_pitch_cd = ahrs.pitch_sensor;
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);
#endif
} else {
// we are doing normal AUTO flight, the special cases
Expand Down
6 changes: 0 additions & 6 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -582,12 +582,6 @@ void Plane::set_throttle(void)
// Update voltage scaling
g2.fwd_batt_cmp.update();

#if AP_SCRIPTING_ENABLED
if (nav_scripting_active()) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);
}
#endif

if (control_mode->use_battery_compensation()) {
// Apply voltage compensation to throttle output from flight mode
const float throttle = g2.fwd_batt_cmp.apply_throttle(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle));
Expand Down

0 comments on commit 03ff3b1

Please sign in to comment.