#include "Plane.h"
float Plane::calc_speed_scaler(void)
{
float aspeed, speed_scaler;
if (ahrs.airspeed_estimate(aspeed)) {
if (aspeed > auto_state.highest_airspeed && arming.is_armed_and_safety_off()) {
auto_state.highest_airspeed = aspeed;
}
const float airspeed_min = MAX(aparm.airspeed_min, MIN_AIRSPEED_MIN);
const float scale_min = MIN(0.5, g.scaling_speed / (2.0 * aparm.airspeed_max));
const float scale_max = MAX(2.0, g.scaling_speed / (0.7 * airspeed_min));
if (aspeed > 0.0001f) {
speed_scaler = g.scaling_speed / aspeed;
} else {
speed_scaler = scale_max;
}
speed_scaler = constrain_float(speed_scaler, scale_min, scale_max);
#if HAL_QUADPLANE_ENABLED
if ((quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) && arming.is_armed_and_safety_off()) {
float threshold = airspeed_min * 0.5;
if (aspeed < threshold) {
float new_scaler = linear_interpolate(0.001, g.scaling_speed / threshold, aspeed, 0, threshold);
speed_scaler = MIN(speed_scaler, new_scaler);
rollController.decay_I();
pitchController.decay_I();
yawController.decay_I();
}
}
#endif
} else if (arming.is_armed_and_safety_off()) {
float throttle_out = MAX(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), 1);
speed_scaler = sqrtf(AP_PLANE_TRIM_THROTTLE_DEFAULT / throttle_out);
speed_scaler = constrain_float(speed_scaler, 0.6f, 1.67f);
} else {
speed_scaler = 1;
}
if (!plane.ahrs.using_airspeed_sensor() &&
(plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) &&
(plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) {
return MIN(speed_scaler, 1.0f) ;
}
return speed_scaler;
}
bool Plane::stick_mixing_enabled(void)
{
if (!rc().has_valid_input()) {
return false;
}
#if AP_FENCE_ENABLED
const bool stickmixing = fence_stickmixing();
#else
const bool stickmixing = true;
#endif
#if HAL_QUADPLANE_ENABLED
if (control_mode == &mode_qrtl &&
quadplane.poscontrol.get_state() >= QuadPlane::QPOS_POSITION1) {
return false;
}
if (quadplane.in_vtol_land_poscontrol()) {
return false;
}
#endif
if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {
if (g.stick_mixing != StickMixing::NONE &&
g.stick_mixing != StickMixing::VTOL_YAW &&
stickmixing) {
return true;
} else {
return false;
}
}
if (failsafe.rc_failsafe && g.fs_action_short == FS_ACTION_SHORT_FBWA) {
return false;
}
return true;
}
void Plane::stabilize_roll()
{
if (fly_inverted()) {
nav_roll_cd += 18000;
if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;
}
const float roll_out = stabilize_roll_get_roll_out();
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_out);
}
float Plane::stabilize_roll_get_roll_out()
{
const float speed_scaler = get_speed_scaler();
#if HAL_QUADPLANE_ENABLED
if (!quadplane.use_fw_attitude_controllers()) {
const auto &pid_info = quadplane.attitude_control->get_rate_roll_pid().get_pid_info();
if (quadplane.option_is_set(QuadPlane::Option::SCALE_FF_ANGLE_P)) {
const float mc_angR = quadplane.attitude_control->get_angle_roll_p().kP()
* quadplane.attitude_control->get_last_angle_P_scale().x;
if (is_positive(mc_angR)) {
rollController.set_ff_scale(MIN(1.0, 1.0 / (mc_angR * rollController.tau())));
}
}
const float roll_out = rollController.get_rate_out(degrees(pid_info.target), speed_scaler);
rollController.decay_I();
return roll_out;
}
#endif
bool disable_integrator = false;
if (control_mode == &mode_stabilize && channel_roll->get_control_in() != 0) {
disable_integrator = true;
}
return rollController.get_servo_out(nav_roll_cd - ahrs.roll_sensor, speed_scaler, disable_integrator,
ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));
}
void Plane::stabilize_pitch()
{
int8_t force_elevator = takeoff_tail_hold();
if (force_elevator != 0) {
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, 45*force_elevator);
return;
}
const float pitch_out = stabilize_pitch_get_pitch_out();
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitch_out);
}
float Plane::stabilize_pitch_get_pitch_out()
{
const float speed_scaler = get_speed_scaler();
#if HAL_QUADPLANE_ENABLED
if (!quadplane.use_fw_attitude_controllers()) {
const auto &pid_info = quadplane.attitude_control->get_rate_pitch_pid().get_pid_info();
if (quadplane.option_is_set(QuadPlane::Option::SCALE_FF_ANGLE_P)) {
const float mc_angP = quadplane.attitude_control->get_angle_pitch_p().kP()
* quadplane.attitude_control->get_last_angle_P_scale().y;
if (is_positive(mc_angP)) {
pitchController.set_ff_scale(MIN(1.0, 1.0 / (mc_angP * pitchController.tau())));
}
}
const int32_t pitch_out = pitchController.get_rate_out(degrees(pid_info.target), speed_scaler);
pitchController.decay_I();
return pitch_out;
}
#endif
#if HAL_QUADPLANE_ENABLED
const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition();
#else
const bool quadplane_in_frwd_transition = false;
#endif
int32_t demanded_pitch = nav_pitch_cd + int32_t(g.pitch_trim * 100.0) + SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * g.kff_throttle_to_pitch;
bool disable_integrator = false;
if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {
disable_integrator = true;
}
if (!quadplane_in_frwd_transition &&
!control_mode->is_vtol_mode() &&
!control_mode->does_auto_throttle() &&
flare_mode == FlareMode::ENABLED_PITCH_TARGET &&
throttle_at_zero()) {
demanded_pitch = landing.get_pitch_cd();
}
return pitchController.get_servo_out(demanded_pitch - ahrs.pitch_sensor, speed_scaler, disable_integrator,
ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));
}
void ModeStabilize::stabilize_stick_mixing_direct()
{
if (!plane.stick_mixing_enabled()) {
return;
}
#if HAL_QUADPLANE_ENABLED
if (!plane.quadplane.allow_stick_mixing()) {
return;
}
#endif
float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);
aileron = plane.channel_roll->stick_mixing(aileron);
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);
float elevator = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);
elevator = plane.channel_pitch->stick_mixing(elevator);
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);
}
void Plane::stabilize_stick_mixing_fbw()
{
if (!stick_mixing_enabled() ||
control_mode == &mode_acro ||
control_mode == &mode_fbwa ||
control_mode == &mode_autotune ||
control_mode == &mode_fbwb ||
control_mode == &mode_cruise ||
#if HAL_QUADPLANE_ENABLED
control_mode == &mode_qstabilize ||
control_mode == &mode_qhover ||
control_mode == &mode_qloiter ||
control_mode == &mode_qland ||
control_mode == &mode_qacro ||
#if QAUTOTUNE_ENABLED
control_mode == &mode_qautotune ||
#endif
!quadplane.allow_stick_mixing() ||
#endif
control_mode == &mode_training) {
return;
}
float roll_input = channel_roll->norm_input_dz();
if (roll_input > 0.5f) {
roll_input = (3*roll_input - 1);
} else if (roll_input < -0.5f) {
roll_input = (3*roll_input + 1);
}
nav_roll_cd += roll_input * roll_limit_cd;
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
if (plane.g.stick_mixing == StickMixing::FBW_NO_PITCH) {
return;
}
if ((control_mode == &mode_loiter) && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {
return;
}
float pitch_input = channel_pitch->norm_input_dz();
if (pitch_input > 0.5f) {
pitch_input = (3*pitch_input - 1);
} else if (pitch_input < -0.5f) {
pitch_input = (3*pitch_input + 1);
}
if (fly_inverted()) {
pitch_input = -pitch_input;
}
const float pitch_range = aparm.pitch_limit_max.get() - pitch_limit_min;
nav_pitch_cd += pitch_input * (pitch_range / 2.0f) * 100;
nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
}
void Plane::stabilize_yaw()
{
bool ground_steering = false;
if (landing.is_flaring()) {
ground_steering = true;
} else {
ground_steering = (channel_roll->get_control_in() == 0 &&
fabsf(relative_altitude) < g.ground_steer_alt);
if (!landing.is_ground_steering_allowed()) {
ground_steering = false;
}
}
float steering_output = 0.0;
if (landing.is_flaring() ||
(steer_state.hold_course_cd != -1 && ground_steering)) {
steering_output = calc_nav_yaw_course();
} else if (ground_steering) {
steering_output = calc_nav_yaw_ground();
}
const float rudder_output = calc_nav_yaw_coordinated();
if (!ground_steering) {
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder_output);
} else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) {
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_output);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);
}
#if HAL_QUADPLANE_ENABLED
quadplane.assist.output_spin_recovery();
#endif
}
void Plane::stabilize()
{
uint32_t now = AP_HAL::millis();
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
quadplane.transition->set_FW_roll_pitch(nav_pitch_cd, nav_roll_cd);
}
#endif
if (now - last_stabilize_ms > 2000) {
control_mode->reset_controllers();
}
last_stabilize_ms = now;
if (control_mode == &mode_training ||
control_mode == &mode_manual) {
plane.control_mode->run();
#if AP_SCRIPTING_ENABLED
} else if (nav_scripting_active()) {
const float speed_scaler = get_speed_scaler();
const float aileron = rollController.get_rate_out(nav_scripting.roll_rate_dps, speed_scaler);
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);
float rudder = 0;
if (yawController.rate_control_enabled()) {
rudder = nav_scripting.rudder_offset_pct * 45;
if (nav_scripting.run_yaw_rate_controller) {
rudder += yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false);
} else {
yawController.reset_I();
}
}
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();
}
if (is_zero(get_throttle_input()) &&
fabsf(relative_altitude) < 5.0f &&
fabsf(barometer.get_climb_rate()) < 0.5f &&
ahrs.groundspeed() < 3) {
rollController.reset_I();
pitchController.reset_I();
yawController.reset_I();
if (ahrs.groundspeed() < 1) {
steerController.reset_I();
}
}
}
void Plane::calc_throttle()
{
if (aparm.throttle_cruise <= 1) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
return;
}
float commanded_throttle = TECS_controller.get_throttle_demand();
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, commanded_throttle);
}
int16_t Plane::calc_nav_yaw_coordinated()
{
const float speed_scaler = get_speed_scaler();
bool disable_integrator = false;
int16_t rudder_in = rudder_input();
int16_t commanded_rudder;
bool using_rate_controller = false;
if (control_mode->is_guided_mode() &&
plane.guided_state.last_forced_rpy_ms.z > 0 &&
millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {
commanded_rudder = plane.guided_state.forced_rpy_cd.z;
} else if (autotuning && g.acro_yaw_rate > 0 && yawController.rate_control_enabled()) {
const float rudd_expo = rudder_in_expo(true);
const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate;
const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(cd_to_rad(nav_roll_cd))/MAX(aparm.airspeed_min,smoothed_airspeed));
commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false);
using_rate_controller = true;
} else {
if (control_mode == &mode_stabilize && rudder_in != 0) {
disable_integrator = true;
}
commanded_rudder = yawController.get_servo_out(speed_scaler, disable_integrator);
commanded_rudder += SRV_Channels::get_output_scaled(SRV_Channel::k_aileron) * g.kff_rudder_mix;
commanded_rudder += rudder_in;
}
if (!using_rate_controller) {
yawController.reset_rate_PID();
}
return constrain_int16(commanded_rudder, -4500, 4500);
}
int16_t Plane::calc_nav_yaw_course(void)
{
int32_t bearing_error_cd = nav_controller->bearing_error_cd();
int16_t steering = steerController.get_steering_out_angle_error(bearing_error_cd);
if (stick_mixing_enabled()) {
steering = channel_rudder->stick_mixing(steering);
}
return constrain_int16(steering, -4500, 4500);
}
int16_t Plane::calc_nav_yaw_ground(void)
{
if (gps.ground_speed() < 1 &&
is_zero(get_throttle_input()) &&
flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&
flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {
steer_state.locked_course = false;
steer_state.locked_course_err = 0;
return rudder_input();
}
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - steer_state.last_steer_ms > 1000) {
steer_state.locked_course = false;
}
steer_state.last_steer_ms = now_ms;
float steer_rate = (rudder_input()/4500.0f) * g.ground_steer_dps;
if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF ||
flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
steer_rate = 0;
}
if (!is_zero(steer_rate)) {
steer_state.locked_course = false;
} else if (!steer_state.locked_course) {
steer_state.locked_course = true;
if (flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&
flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {
steer_state.locked_course_err = 0;
}
}
int16_t steering;
if (!steer_state.locked_course) {
steering = steerController.get_steering_out_rate(steer_rate);
} else {
int32_t yaw_error_cd = -degrees(steer_state.locked_course_err)*100;
steering = steerController.get_steering_out_angle_error(yaw_error_cd);
}
return constrain_int16(steering, -4500, 4500);
}
void Plane::calc_nav_pitch()
{
int32_t commanded_pitch = TECS_controller.get_pitch_demand();
nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);
}
void Plane::calc_nav_roll()
{
int32_t commanded_roll = nav_controller->nav_roll_cd();
nav_roll_cd = constrain_int32(commanded_roll, -roll_limit_cd, roll_limit_cd);
update_load_factor();
}
void Plane::adjust_nav_pitch_throttle(void)
{
int8_t throttle = throttle_percentage();
if (throttle >= 0 && throttle < aparm.throttle_cruise && flight_stage != AP_FixedWing::FlightStage::VTOL) {
float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;
nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;
}
}
void Plane::update_load_factor(void)
{
float demanded_roll = fabsf(nav_roll_cd*0.01f);
if (demanded_roll > 85) {
demanded_roll = 85;
}
aerodynamic_load_factor = 1.0f / cosf(radians(demanded_roll));
apply_load_factor_roll_limits();
}
void Plane::apply_load_factor_roll_limits(void)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.available() && quadplane.transition->set_FW_roll_limit(roll_limit_cd)) {
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
return;
}
#endif
if (!aparm.stall_prevention) {
return;
}
if (fly_inverted()) {
return;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.tailsitter.active()) {
return;
}
#endif
float stall_airspeed_1g = is_positive(aparm.airspeed_stall)
? aparm.airspeed_stall
: aparm.airspeed_min;
float max_load_factor =
sq(smoothed_airspeed / MAX(stall_airspeed_1g, 1));
const bool enforce_full_roll_limit =
flight_option_enabled(FlightOptions::ENABLE_FULL_AERO_LF_ROLL_LIMITS) &&
ahrs.using_airspeed_sensor() && is_positive(aparm.airspeed_stall);
const float level_roll_limit_deg = g.level_roll_limit;
float lf_roll_limit_deg = aparm.roll_limit;
if (max_load_factor <= 1) {
if (enforce_full_roll_limit) {
lf_roll_limit_deg = level_roll_limit_deg;
} else {
lf_roll_limit_deg = 25;
}
} else if (max_load_factor < aerodynamic_load_factor) {
lf_roll_limit_deg = degrees(acosf(1.0f / max_load_factor));
if (!enforce_full_roll_limit && lf_roll_limit_deg < 25) {
lf_roll_limit_deg = 25;
}
if (lf_roll_limit_deg < level_roll_limit_deg) {
lf_roll_limit_deg = level_roll_limit_deg;
}
}
nav_roll_cd = constrain_int32(nav_roll_cd, -lf_roll_limit_deg * 100, lf_roll_limit_deg * 100);
roll_limit_cd = MIN(roll_limit_cd, lf_roll_limit_deg * 100);
}