Plane: use yaw rate controller in NAV_SCRIPT_TIME

This commit is contained in:
Andrew Tridgell 2021-11-26 10:18:13 +11:00 committed by Peter Barker
parent 55d8afa1dd
commit 56870ad7d6
3 changed files with 6 additions and 0 deletions

View File

@ -519,6 +519,10 @@ void Plane::stabilize()
const float elevator = pitchController.get_rate_out(nav_scripting.pitch_rate_dps, speed_scaler);
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
if (yawController.rate_control_enabled()) {
const float rudder = yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false);
steering_control.rudder = rudder;
}
#endif
} else {
if (allow_stick_mixing && g.stick_mixing == StickMixing::FBW && control_mode != &mode_stabilize) {

View File

@ -523,6 +523,7 @@ private:
uint16_t id;
float roll_rate_dps;
float pitch_rate_dps;
float yaw_rate_dps;
float throttle_pct;
uint32_t start_ms;
bool done;

View File

@ -1188,6 +1188,7 @@ bool Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps
}
nav_scripting.roll_rate_dps = roll_rate_dps;
nav_scripting.pitch_rate_dps = pitch_rate_dps;
nav_scripting.yaw_rate_dps = yaw_rate_dps;
nav_scripting.throttle_pct = throttle_pct;
return true;
}