Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/Attitude.cpp
Views: 1798
#include "Plane.h"12/*3calculate speed scaling number for control surfaces. This is applied4to PIDs to change the scaling of the PID with speed. At high speed5we move the surfaces less, and at low speeds we move them more.6*/7float Plane::calc_speed_scaler(void)8{9float aspeed, speed_scaler;10if (ahrs.airspeed_estimate(aspeed)) {11if (aspeed > auto_state.highest_airspeed && arming.is_armed_and_safety_off()) {12auto_state.highest_airspeed = aspeed;13}14// ensure we have scaling over the full configured airspeed15const float airspeed_min = MAX(aparm.airspeed_min, MIN_AIRSPEED_MIN);16const float scale_min = MIN(0.5, g.scaling_speed / (2.0 * aparm.airspeed_max));17const float scale_max = MAX(2.0, g.scaling_speed / (0.7 * airspeed_min));18if (aspeed > 0.0001f) {19speed_scaler = g.scaling_speed / aspeed;20} else {21speed_scaler = scale_max;22}23speed_scaler = constrain_float(speed_scaler, scale_min, scale_max);2425#if HAL_QUADPLANE_ENABLED26if (quadplane.in_vtol_mode() && arming.is_armed_and_safety_off()) {27// when in VTOL modes limit surface movement at low speed to prevent instability28float threshold = airspeed_min * 0.5;29if (aspeed < threshold) {30float new_scaler = linear_interpolate(0.001, g.scaling_speed / threshold, aspeed, 0, threshold);31speed_scaler = MIN(speed_scaler, new_scaler);3233// we also decay the integrator to prevent an integrator from before34// we were at low speed persistent at high speed35rollController.decay_I();36pitchController.decay_I();37yawController.decay_I();38}39}40#endif41} else if (arming.is_armed_and_safety_off()) {42// scale assumed surface movement using throttle output43float throttle_out = MAX(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), 1);44speed_scaler = sqrtf(THROTTLE_CRUISE / throttle_out);45// This case is constrained tighter as we don't have real speed info46speed_scaler = constrain_float(speed_scaler, 0.6f, 1.67f);47} else {48// no speed estimate and not armed, use a unit scaling49speed_scaler = 1;50}51if (!plane.ahrs.using_airspeed_sensor() &&52(plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) &&53(plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates54return MIN(speed_scaler, 1.0f) ;55}56return speed_scaler;57}5859/*60return true if the current settings and mode should allow for stick mixing61*/62bool Plane::stick_mixing_enabled(void)63{64if (!rc().has_valid_input()) {65// never stick mix without valid RC66return false;67}68#if AP_FENCE_ENABLED69const bool stickmixing = fence_stickmixing();70#else71const bool stickmixing = true;72#endif73#if HAL_QUADPLANE_ENABLED74if (control_mode == &mode_qrtl &&75quadplane.poscontrol.get_state() >= QuadPlane::QPOS_POSITION1) {76// user may be repositioning77return false;78}79if (quadplane.in_vtol_land_poscontrol()) {80// user may be repositioning81return false;82}83#endif84if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {85// we're in an auto mode. Check the stick mixing flag86if (g.stick_mixing != StickMixing::NONE &&87g.stick_mixing != StickMixing::VTOL_YAW &&88stickmixing) {89return true;90} else {91return false;92}93}9495if (failsafe.rc_failsafe && g.fs_action_short == FS_ACTION_SHORT_FBWA) {96// don't do stick mixing in FBWA glide mode97return false;98}99100// non-auto mode. Always do stick mixing101return true;102}103104105/*106this is the main roll stabilization function. It takes the107previously set nav_roll calculates roll servo_out to try to108stabilize the plane at the given roll109*/110void Plane::stabilize_roll()111{112if (fly_inverted()) {113// we want to fly upside down. We need to cope with wrap of114// the roll_sensor interfering with wrap of nav_roll, which115// would really confuse the PID code. The easiest way to116// handle this is to ensure both go in the same direction from117// zero118nav_roll_cd += 18000;119if (ahrs.roll_sensor < 0) nav_roll_cd -= 36000;120}121122const float roll_out = stabilize_roll_get_roll_out();123SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, roll_out);124}125126float Plane::stabilize_roll_get_roll_out()127{128const float speed_scaler = get_speed_scaler();129#if HAL_QUADPLANE_ENABLED130if (!quadplane.use_fw_attitude_controllers()) {131// use the VTOL rate for control, to ensure consistency132const auto &pid_info = quadplane.attitude_control->get_rate_roll_pid().get_pid_info();133134// scale FF to angle P135if (quadplane.option_is_set(QuadPlane::OPTION::SCALE_FF_ANGLE_P)) {136const float mc_angR = quadplane.attitude_control->get_angle_roll_p().kP()137* quadplane.attitude_control->get_last_angle_P_scale().x;138if (is_positive(mc_angR)) {139rollController.set_ff_scale(MIN(1.0, 1.0 / (mc_angR * rollController.tau())));140}141}142143const float roll_out = rollController.get_rate_out(degrees(pid_info.target), speed_scaler);144/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent145opposing integrators balancing between the two controllers146*/147rollController.decay_I();148return roll_out;149}150#endif151152bool disable_integrator = false;153if (control_mode == &mode_stabilize && channel_roll->get_control_in() != 0) {154disable_integrator = true;155}156return rollController.get_servo_out(nav_roll_cd - ahrs.roll_sensor, speed_scaler, disable_integrator,157ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));158}159160/*161this is the main pitch stabilization function. It takes the162previously set nav_pitch and calculates servo_out values to try to163stabilize the plane at the given attitude.164*/165void Plane::stabilize_pitch()166{167int8_t force_elevator = takeoff_tail_hold();168if (force_elevator != 0) {169// we are holding the tail down during takeoff. Just convert170// from a percentage to a -4500..4500 centidegree angle171SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, 45*force_elevator);172return;173}174175const float pitch_out = stabilize_pitch_get_pitch_out();176SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, pitch_out);177}178179float Plane::stabilize_pitch_get_pitch_out()180{181const float speed_scaler = get_speed_scaler();182#if HAL_QUADPLANE_ENABLED183if (!quadplane.use_fw_attitude_controllers()) {184// use the VTOL rate for control, to ensure consistency185const auto &pid_info = quadplane.attitude_control->get_rate_pitch_pid().get_pid_info();186187// scale FF to angle P188if (quadplane.option_is_set(QuadPlane::OPTION::SCALE_FF_ANGLE_P)) {189const float mc_angP = quadplane.attitude_control->get_angle_pitch_p().kP()190* quadplane.attitude_control->get_last_angle_P_scale().y;191if (is_positive(mc_angP)) {192pitchController.set_ff_scale(MIN(1.0, 1.0 / (mc_angP * pitchController.tau())));193}194}195196const int32_t pitch_out = pitchController.get_rate_out(degrees(pid_info.target), speed_scaler);197/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent198opposing integrators balancing between the two controllers199*/200pitchController.decay_I();201return pitch_out;202}203#endif204// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set205#if HAL_QUADPLANE_ENABLED206const bool quadplane_in_frwd_transition = quadplane.in_frwd_transition();207#else208const bool quadplane_in_frwd_transition = false;209#endif210211int32_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;212bool disable_integrator = false;213if (control_mode == &mode_stabilize && channel_pitch->get_control_in() != 0) {214disable_integrator = true;215}216/* force landing pitch if:217- flare switch high218- throttle stick at zero thrust219- in fixed wing non auto-throttle mode220*/221if (!quadplane_in_frwd_transition &&222!control_mode->is_vtol_mode() &&223!control_mode->does_auto_throttle() &&224flare_mode == FlareMode::ENABLED_PITCH_TARGET &&225throttle_at_zero()) {226demanded_pitch = landing.get_pitch_cd();227}228229return pitchController.get_servo_out(demanded_pitch - ahrs.pitch_sensor, speed_scaler, disable_integrator,230ground_mode && !(plane.flight_option_enabled(FlightOptions::DISABLE_GROUND_PID_SUPPRESSION)));231}232233/*234this gives the user control of the aircraft in stabilization modes, only used in Stabilize Mode235to be moved to mode_stabilize.cpp in future236*/237void ModeStabilize::stabilize_stick_mixing_direct()238{239if (!plane.stick_mixing_enabled()) {240return;241}242#if HAL_QUADPLANE_ENABLED243if (!plane.quadplane.allow_stick_mixing()) {244return;245}246#endif247float aileron = SRV_Channels::get_output_scaled(SRV_Channel::k_aileron);248aileron = plane.channel_roll->stick_mixing(aileron);249SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);250251float elevator = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator);252elevator = plane.channel_pitch->stick_mixing(elevator);253SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);254}255256/*257this gives the user control of the aircraft in stabilization modes258using FBW style controls259*/260void Plane::stabilize_stick_mixing_fbw()261{262if (!stick_mixing_enabled() ||263control_mode == &mode_acro ||264control_mode == &mode_fbwa ||265control_mode == &mode_autotune ||266control_mode == &mode_fbwb ||267control_mode == &mode_cruise ||268#if HAL_QUADPLANE_ENABLED269control_mode == &mode_qstabilize ||270control_mode == &mode_qhover ||271control_mode == &mode_qloiter ||272control_mode == &mode_qland ||273control_mode == &mode_qacro ||274#if QAUTOTUNE_ENABLED275control_mode == &mode_qautotune ||276#endif277!quadplane.allow_stick_mixing() ||278#endif // HAL_QUADPLANE_ENABLED279control_mode == &mode_training) {280return;281}282// do FBW style stick mixing. We don't treat it linearly283// however. For inputs up to half the maximum, we use linear284// addition to the nav_roll and nav_pitch. Above that it goes285// non-linear and ends up as 2x the maximum, to ensure that286// the user can direct the plane in any direction with stick287// mixing.288float roll_input = channel_roll->norm_input_dz();289if (roll_input > 0.5f) {290roll_input = (3*roll_input - 1);291} else if (roll_input < -0.5f) {292roll_input = (3*roll_input + 1);293}294nav_roll_cd += roll_input * roll_limit_cd;295nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);296297if ((control_mode == &mode_loiter) && (plane.flight_option_enabled(FlightOptions::ENABLE_LOITER_ALT_CONTROL))) {298// loiter is using altitude control based on the pitch stick, don't use it again here299return;300}301302float pitch_input = channel_pitch->norm_input_dz();303if (pitch_input > 0.5f) {304pitch_input = (3*pitch_input - 1);305} else if (pitch_input < -0.5f) {306pitch_input = (3*pitch_input + 1);307}308if (fly_inverted()) {309pitch_input = -pitch_input;310}311if (pitch_input > 0) {312nav_pitch_cd += pitch_input * aparm.pitch_limit_max*100;313} else {314nav_pitch_cd += -(pitch_input * pitch_limit_min*100);315}316nav_pitch_cd = constrain_int32(nav_pitch_cd, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);317}318319320/*321stabilize the yaw axis. There are 3 modes of operation:322323- hold a specific heading with ground steering324- rate controlled with ground steering325- yaw control for coordinated flight326*/327void Plane::stabilize_yaw()328{329bool ground_steering = false;330if (landing.is_flaring()) {331// in flaring then enable ground steering332ground_steering = true;333} else {334// otherwise use ground steering when no input control and we335// are below the GROUND_STEER_ALT336ground_steering = (channel_roll->get_control_in() == 0 &&337fabsf(relative_altitude) < g.ground_steer_alt);338if (!landing.is_ground_steering_allowed()) {339// don't use ground steering on landing approach340ground_steering = false;341}342}343344345/*346first calculate steering for a nose or tail347wheel. We use "course hold" mode for the rudder when either performing348a flare (when the wings are held level) or when in course hold in349FBWA mode (when we are below GROUND_STEER_ALT)350*/351float steering_output = 0.0;352if (landing.is_flaring() ||353(steer_state.hold_course_cd != -1 && ground_steering)) {354steering_output = calc_nav_yaw_course();355} else if (ground_steering) {356steering_output = calc_nav_yaw_ground();357}358359/*360now calculate rudder for the rudder361*/362const float rudder_output = calc_nav_yaw_coordinated();363364if (!ground_steering) {365// Not doing ground steering, output rudder on steering channel366SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);367SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder_output);368369} else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) {370// Ground steering active but no steering output configured, output steering on rudder channel371SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_output);372SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);373374} else {375// Ground steering with both steering and rudder channels376SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output);377SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output);378}379380}381382/*383main stabilization function for all 3 axes384*/385void Plane::stabilize()386{387uint32_t now = AP_HAL::millis();388#if HAL_QUADPLANE_ENABLED389if (quadplane.available()) {390quadplane.transition->set_FW_roll_pitch(nav_pitch_cd, nav_roll_cd);391}392#endif393394if (now - last_stabilize_ms > 2000) {395// if we haven't run the rate controllers for 2 seconds then reset396control_mode->reset_controllers();397}398last_stabilize_ms = now;399400if (control_mode == &mode_training ||401control_mode == &mode_manual) {402plane.control_mode->run();403#if AP_SCRIPTING_ENABLED404} else if (nav_scripting_active()) {405// scripting is in control of roll and pitch rates and throttle406const float speed_scaler = get_speed_scaler();407const float aileron = rollController.get_rate_out(nav_scripting.roll_rate_dps, speed_scaler);408const float elevator = pitchController.get_rate_out(nav_scripting.pitch_rate_dps, speed_scaler);409SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron);410SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator);411float rudder = 0;412if (yawController.rate_control_enabled()) {413rudder = nav_scripting.rudder_offset_pct * 45;414if (nav_scripting.run_yaw_rate_controller) {415rudder += yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false);416} else {417yawController.reset_I();418}419}420SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder);421SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder);422SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct);423#endif424} else {425plane.control_mode->run();426}427428/*429see if we should zero the attitude controller integrators.430*/431if (is_zero(get_throttle_input()) &&432fabsf(relative_altitude) < 5.0f &&433fabsf(barometer.get_climb_rate()) < 0.5f &&434ahrs.groundspeed() < 3) {435// we are low, with no climb rate, and zero throttle, and very436// low ground speed. Zero the attitude controller437// integrators. This prevents integrator buildup pre-takeoff.438rollController.reset_I();439pitchController.reset_I();440yawController.reset_I();441442// if moving very slowly also zero the steering integrator443if (ahrs.groundspeed() < 1) {444steerController.reset_I();445}446}447}448449450/*451* Set the throttle output.452* This is called by TECS-enabled flight modes, e.g. AUTO, GUIDED, etc.453*/454void Plane::calc_throttle()455{456if (aparm.throttle_cruise <= 1) {457// user has asked for zero throttle - this may be done by a458// mission which wants to turn off the engine for a parachute459// landing460SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);461return;462}463464// Read the TECS throttle output and set it to the throttle channel.465float commanded_throttle = TECS_controller.get_throttle_demand();466SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, commanded_throttle);467}468469/*****************************************470* Calculate desired roll/pitch/yaw angles (in medium freq loop)471*****************************************/472473/*474calculate yaw control for coordinated flight475*/476int16_t Plane::calc_nav_yaw_coordinated()477{478const float speed_scaler = get_speed_scaler();479bool disable_integrator = false;480int16_t rudder_in = rudder_input();481482int16_t commanded_rudder;483bool using_rate_controller = false;484485// Received an external msg that guides yaw in the last 3 seconds?486if (control_mode->is_guided_mode() &&487plane.guided_state.last_forced_rpy_ms.z > 0 &&488millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {489commanded_rudder = plane.guided_state.forced_rpy_cd.z;490} else if (autotuning && g.acro_yaw_rate > 0 && yawController.rate_control_enabled()) {491// user is doing an AUTOTUNE with yaw rate control492const float rudd_expo = rudder_in_expo(true);493const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate;494// add in the coordinated turn yaw rate to make it easier to fly while tuning the yaw rate controller495const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(radians(nav_roll_cd*0.01f))/MAX(aparm.airspeed_min,smoothed_airspeed));496commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false);497using_rate_controller = true;498} else {499if (control_mode == &mode_stabilize && rudder_in != 0) {500disable_integrator = true;501}502503commanded_rudder = yawController.get_servo_out(speed_scaler, disable_integrator);504505// add in rudder mixing from roll506commanded_rudder += SRV_Channels::get_output_scaled(SRV_Channel::k_aileron) * g.kff_rudder_mix;507commanded_rudder += rudder_in;508}509510if (!using_rate_controller) {511/*512When not running the yaw rate controller, we need to reset the rate513*/514yawController.reset_rate_PID();515}516517return constrain_int16(commanded_rudder, -4500, 4500);518}519520/*521calculate yaw control for ground steering with specific course522*/523int16_t Plane::calc_nav_yaw_course(void)524{525// holding a specific navigation course on the ground. Used in526// auto-takeoff and landing527int32_t bearing_error_cd = nav_controller->bearing_error_cd();528int16_t steering = steerController.get_steering_out_angle_error(bearing_error_cd);529if (stick_mixing_enabled()) {530steering = channel_rudder->stick_mixing(steering);531}532return constrain_int16(steering, -4500, 4500);533}534535/*536calculate yaw control for ground steering537*/538int16_t Plane::calc_nav_yaw_ground(void)539{540if (gps.ground_speed() < 1 &&541is_zero(get_throttle_input()) &&542flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&543flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {544// manual rudder control while still545steer_state.locked_course = false;546steer_state.locked_course_err = 0;547return rudder_input();548}549550// if we haven't been steering for 1s then clear locked course551const uint32_t now_ms = AP_HAL::millis();552if (now_ms - steer_state.last_steer_ms > 1000) {553steer_state.locked_course = false;554}555steer_state.last_steer_ms = now_ms;556557float steer_rate = (rudder_input()/4500.0f) * g.ground_steer_dps;558if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF ||559flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {560steer_rate = 0;561}562if (!is_zero(steer_rate)) {563// pilot is giving rudder input564steer_state.locked_course = false;565} else if (!steer_state.locked_course) {566// pilot has released the rudder stick or we are still - lock the course567steer_state.locked_course = true;568if (flight_stage != AP_FixedWing::FlightStage::TAKEOFF &&569flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) {570steer_state.locked_course_err = 0;571}572}573574int16_t steering;575if (!steer_state.locked_course) {576// use a rate controller at the pilot specified rate577steering = steerController.get_steering_out_rate(steer_rate);578} else {579// use a error controller on the summed error580int32_t yaw_error_cd = -ToDeg(steer_state.locked_course_err)*100;581steering = steerController.get_steering_out_angle_error(yaw_error_cd);582}583return constrain_int16(steering, -4500, 4500);584}585586587/*588calculate a new nav_pitch_cd from the speed height controller589*/590void Plane::calc_nav_pitch()591{592int32_t commanded_pitch = TECS_controller.get_pitch_demand();593nav_pitch_cd = constrain_int32(commanded_pitch, pitch_limit_min*100, aparm.pitch_limit_max.get()*100);594}595596597/*598calculate a new nav_roll_cd from the navigation controller599*/600void Plane::calc_nav_roll()601{602int32_t commanded_roll = nav_controller->nav_roll_cd();603nav_roll_cd = constrain_int32(commanded_roll, -roll_limit_cd, roll_limit_cd);604update_load_factor();605}606607/*608adjust nav_pitch_cd for STAB_PITCH_DOWN_CD. This is used to make609keeping up good airspeed in FBWA mode easier, as the plane will610automatically pitch down a little when at low throttle. It makes611FBWA landings without stalling much easier.612*/613void Plane::adjust_nav_pitch_throttle(void)614{615int8_t throttle = throttle_percentage();616if (throttle >= 0 && throttle < aparm.throttle_cruise && flight_stage != AP_FixedWing::FlightStage::VTOL) {617float p = (aparm.throttle_cruise - throttle) / (float)aparm.throttle_cruise;618nav_pitch_cd -= g.stab_pitch_down * 100.0f * p;619}620}621622623/*624calculate a new aerodynamic_load_factor and limit nav_roll_cd to625ensure that the load factor does not take us below the sustainable626airspeed627*/628void Plane::update_load_factor(void)629{630float demanded_roll = fabsf(nav_roll_cd*0.01f);631if (demanded_roll > 85) {632// limit to 85 degrees to prevent numerical errors633demanded_roll = 85;634}635aerodynamic_load_factor = 1.0f / safe_sqrt(cosf(radians(demanded_roll)));636637#if HAL_QUADPLANE_ENABLED638if (quadplane.available() && quadplane.transition->set_FW_roll_limit(roll_limit_cd)) {639nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);640return;641}642#endif643644if (!aparm.stall_prevention) {645// stall prevention is disabled646return;647}648if (fly_inverted()) {649// no roll limits when inverted650return;651}652#if HAL_QUADPLANE_ENABLED653if (quadplane.tailsitter.active()) {654// no limits while hovering655return;656}657#endif658659float max_load_factor = smoothed_airspeed / MAX(aparm.airspeed_min, 1);660if (max_load_factor <= 1) {661// our airspeed is below the minimum airspeed. Limit roll to662// 25 degrees663nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500);664roll_limit_cd = MIN(roll_limit_cd, 2500);665} else if (max_load_factor < aerodynamic_load_factor) {666// the demanded nav_roll would take us past the aerodynamic667// load limit. Limit our roll to a bank angle that will keep668// the load within what the airframe can handle. We always669// allow at least 25 degrees of roll however, to ensure the670// aircraft can be manoeuvred with a bad airspeed estimate. At671// 25 degrees the load factor is 1.1 (10%)672int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100;673if (roll_limit < 2500) {674roll_limit = 2500;675}676nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);677roll_limit_cd = MIN(roll_limit_cd, roll_limit);678}679}680681682