mirror of https://github.com/ArduPilot/ardupilot
Plane: output nav scripting throttle with rest of nav scripting stuff
This commit is contained in:
parent
3aa742e1b9
commit
6b32227d2f
|
@ -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();
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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));
|
||||
|
|
Loading…
Reference in New Issue