2015-05-13 03:09:36 -03:00
# include "Plane.h"
2011-09-08 22:29:39 -03:00
2012-09-11 00:01:36 -03:00
/*
2021-12-28 21:23:09 -04:00
calculate speed scaling number for control surfaces . This is applied
to PIDs to change the scaling of the PID with speed . At high speed
we move the surfaces less , and at low speeds we move them more .
2012-09-11 00:01:36 -03:00
*/
2021-12-28 21:23:09 -04:00
float Plane : : calc_speed_scaler ( void )
2012-09-11 00:01:36 -03:00
{
float aspeed , speed_scaler ;
2020-01-06 20:45:27 -04:00
if ( ahrs . airspeed_estimate ( aspeed ) ) {
2023-02-10 22:36:33 -04:00
if ( aspeed > auto_state . highest_airspeed & & arming . is_armed_and_safety_off ( ) ) {
2014-05-21 07:21:19 -03:00
auto_state . highest_airspeed = aspeed ;
}
2022-09-03 14:34:23 -03:00
// ensure we have scaling over the full configured airspeed
2022-09-04 20:10:01 -03:00
const float airspeed_min = MAX ( aparm . airspeed_min , MIN_AIRSPEED_MIN ) ;
2022-09-03 14:34:23 -03:00
const float scale_min = MIN ( 0.5 , g . scaling_speed / ( 2.0 * aparm . airspeed_max ) ) ;
2022-09-04 20:10:01 -03:00
const float scale_max = MAX ( 2.0 , g . scaling_speed / ( 0.7 * airspeed_min ) ) ;
2016-06-04 06:20:18 -03:00
if ( aspeed > 0.0001f ) {
2012-08-21 23:19:50 -03:00
speed_scaler = g . scaling_speed / aspeed ;
2012-07-15 22:21:50 -03:00
} else {
2022-09-03 14:34:23 -03:00
speed_scaler = scale_max ;
2012-07-15 22:21:50 -03:00
}
2018-11-02 00:56:06 -03:00
speed_scaler = constrain_float ( speed_scaler , scale_min , scale_max ) ;
2018-09-13 00:49:58 -03:00
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2023-02-10 22:36:33 -04:00
if ( quadplane . in_vtol_mode ( ) & & arming . is_armed_and_safety_off ( ) ) {
2018-09-13 00:49:58 -03:00
// when in VTOL modes limit surface movement at low speed to prevent instability
2022-09-04 20:10:01 -03:00
float threshold = airspeed_min * 0.5 ;
2018-09-13 00:49:58 -03:00
if ( aspeed < threshold ) {
2020-06-22 01:45:50 -03:00
float new_scaler = linear_interpolate ( 0.001 , g . scaling_speed / threshold , aspeed , 0 , threshold ) ;
2018-09-13 00:49:58 -03:00
speed_scaler = MIN ( speed_scaler , new_scaler ) ;
2019-07-06 22:22:52 -03:00
// we also decay the integrator to prevent an integrator from before
2023-10-11 04:41:54 -03:00
// we were at low speed persistent at high speed
2019-07-06 22:22:52 -03:00
rollController . decay_I ( ) ;
pitchController . decay_I ( ) ;
yawController . decay_I ( ) ;
2018-09-13 00:49:58 -03:00
}
}
2021-09-10 03:28:21 -03:00
# endif
2023-02-10 22:36:33 -04:00
} else if ( arming . is_armed_and_safety_off ( ) ) {
2018-12-06 00:29:08 -04:00
// scale assumed surface movement using throttle output
float throttle_out = MAX ( SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) , 1 ) ;
speed_scaler = sqrtf ( THROTTLE_CRUISE / throttle_out ) ;
2012-08-24 09:03:03 -03:00
// This case is constrained tighter as we don't have real speed info
2015-04-11 06:43:13 -03:00
speed_scaler = constrain_float ( speed_scaler , 0.6f , 1.67f ) ;
2018-12-06 00:29:08 -04:00
} else {
// no speed estimate and not armed, use a unit scaling
speed_scaler = 1 ;
2012-08-21 23:19:50 -03:00
}
2023-10-23 22:41:37 -03:00
if ( ! plane . ahrs . using_airspeed_sensor ( ) & &
2023-04-26 00:27:13 -03:00
( plane . flight_option_enabled ( FlightOptions : : SURPRESS_TKOFF_SCALING ) ) & &
2023-10-11 04:41:54 -03:00
( 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 estimates
2021-04-16 17:01:59 -03:00
return MIN ( speed_scaler , 1.0f ) ;
}
2012-09-11 00:01:36 -03:00
return speed_scaler ;
}
2012-09-22 20:33:17 -03:00
/*
return true if the current settings and mode should allow for stick mixing
*/
2015-05-13 03:09:36 -03:00
bool Plane : : stick_mixing_enabled ( void )
2012-09-22 20:33:17 -03:00
{
2022-03-08 11:05:19 -04:00
if ( ! rc ( ) . has_valid_input ( ) ) {
// never stick mix without valid RC
return false ;
}
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2020-12-14 08:47:05 -04:00
const bool stickmixing = fence_stickmixing ( ) ;
# else
const bool stickmixing = true ;
# endif
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-06-08 03:00:54 -03:00
if ( control_mode = = & mode_qrtl & &
quadplane . poscontrol . get_state ( ) > = QuadPlane : : QPOS_POSITION1 ) {
// user may be repositioning
return false ;
}
if ( quadplane . in_vtol_land_poscontrol ( ) ) {
// user may be repositioning
return false ;
}
2021-09-10 03:28:21 -03:00
# endif
2020-12-23 01:25:35 -04:00
if ( control_mode - > does_auto_throttle ( ) & & plane . control_mode - > does_auto_navigation ( ) ) {
2012-09-23 18:13:57 -03:00
// we're in an auto mode. Check the stick mixing flag
2021-11-02 19:57:51 -03:00
if ( g . stick_mixing ! = StickMixing : : NONE & &
g . stick_mixing ! = StickMixing : : VTOL_YAW & &
2022-03-08 11:05:19 -04:00
stickmixing ) {
2012-09-23 18:13:57 -03:00
return true ;
} else {
return false ;
}
2012-09-22 20:33:17 -03:00
}
2013-09-13 21:30:13 -03:00
2017-12-06 19:02:11 -04:00
if ( failsafe . rc_failsafe & & g . fs_action_short = = FS_ACTION_SHORT_FBWA ) {
2013-09-13 21:30:13 -03:00
// don't do stick mixing in FBWA glide mode
return false ;
}
2012-09-23 18:13:57 -03:00
// non-auto mode. Always do stick mixing
return true ;
2012-09-22 20:33:17 -03:00
}
2012-09-11 00:01:36 -03:00
2012-12-04 02:32:37 -04:00
/*
this is the main roll stabilization function . It takes the
previously set nav_roll calculates roll servo_out to try to
stabilize the plane at the given roll
*/
2023-02-01 07:17:27 -04:00
void Plane : : stabilize_roll ( )
2012-09-11 00:01:36 -03:00
{
2014-06-05 03:12:10 -03:00
if ( fly_inverted ( ) ) {
2011-09-09 11:18:38 -03:00
// we want to fly upside down. We need to cope with wrap of
// the roll_sensor interfering with wrap of nav_roll, which
// would really confuse the PID code. The easiest way to
// handle this is to ensure both go in the same direction from
// zero
2012-08-07 03:05:51 -03:00
nav_roll_cd + = 18000 ;
if ( ahrs . roll_sensor < 0 ) nav_roll_cd - = 36000 ;
2011-09-09 11:18:38 -03:00
}
2023-02-01 07:17:27 -04:00
const float roll_out = stabilize_roll_get_roll_out ( ) ;
2021-09-10 03:28:21 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_aileron , roll_out ) ;
}
2023-02-01 07:17:27 -04:00
float Plane : : stabilize_roll_get_roll_out ( )
2021-09-10 03:28:21 -03:00
{
2023-02-01 07:17:27 -04:00
const float speed_scaler = get_speed_scaler ( ) ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-05-18 00:44:57 -03:00
if ( ! quadplane . use_fw_attitude_controllers ( ) ) {
// use the VTOL rate for control, to ensure consistency
const auto & pid_info = quadplane . attitude_control - > get_rate_roll_pid ( ) . get_pid_info ( ) ;
2023-07-03 15:51:36 -03:00
// scale FF to angle P
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 ( ) ) ) ) ;
}
}
2021-09-18 15:05:13 -03:00
const float roll_out = rollController . get_rate_out ( degrees ( pid_info . target ) , speed_scaler ) ;
2021-05-18 00:44:57 -03:00
/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent
opposing integrators balancing between the two controllers
*/
rollController . decay_I ( ) ;
2021-09-10 03:28:21 -03:00
return roll_out ;
2021-05-18 00:44:57 -03:00
}
2021-09-10 03:28:21 -03:00
# endif
bool disable_integrator = false ;
if ( control_mode = = & mode_stabilize & & channel_roll - > get_control_in ( ) ! = 0 ) {
disable_integrator = true ;
}
2021-10-29 07:37:52 -03:00
return rollController . get_servo_out ( nav_roll_cd - ahrs . roll_sensor , speed_scaler , disable_integrator ,
2023-04-26 00:27:13 -03:00
ground_mode & & ! ( plane . flight_option_enabled ( FlightOptions : : DISABLE_GROUND_PID_SUPPRESSION ) ) ) ;
2012-12-04 02:32:37 -04:00
}
/*
this is the main pitch stabilization function . It takes the
previously set nav_pitch and calculates servo_out values to try to
stabilize the plane at the given attitude .
*/
2023-02-01 07:17:27 -04:00
void Plane : : stabilize_pitch ( )
2012-12-04 02:32:37 -04:00
{
2014-05-21 07:21:19 -03:00
int8_t force_elevator = takeoff_tail_hold ( ) ;
if ( force_elevator ! = 0 ) {
2016-01-30 03:22:21 -04:00
// we are holding the tail down during takeoff. Just convert
2014-05-21 07:21:19 -03:00
// from a percentage to a -4500..4500 centidegree angle
2016-10-22 07:27:57 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_elevator , 45 * force_elevator ) ;
2014-05-21 07:21:19 -03:00
return ;
}
2020-10-02 21:52:56 -03:00
2023-02-01 07:17:27 -04:00
const float pitch_out = stabilize_pitch_get_pitch_out ( ) ;
2021-09-10 03:28:21 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_elevator , pitch_out ) ;
}
2023-02-01 07:17:27 -04:00
float Plane : : stabilize_pitch_get_pitch_out ( )
2021-09-10 03:28:21 -03:00
{
2023-02-01 07:17:27 -04:00
const float speed_scaler = get_speed_scaler ( ) ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-05-18 00:44:57 -03:00
if ( ! quadplane . use_fw_attitude_controllers ( ) ) {
// use the VTOL rate for control, to ensure consistency
const auto & pid_info = quadplane . attitude_control - > get_rate_pitch_pid ( ) . get_pid_info ( ) ;
2023-07-03 15:51:36 -03:00
// scale FF to angle P
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 ( ) ) ) ) ;
}
}
2021-09-10 03:28:21 -03:00
const int32_t pitch_out = pitchController . get_rate_out ( degrees ( pid_info . target ) , speed_scaler ) ;
2021-05-18 00:44:57 -03:00
/* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent
opposing integrators balancing between the two controllers
*/
pitchController . decay_I ( ) ;
2021-09-10 03:28:21 -03:00
return pitch_out ;
}
# endif
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
# if HAL_QUADPLANE_ENABLED
const bool quadplane_in_transition = quadplane . in_transition ( ) ;
# else
const bool quadplane_in_transition = false ;
# endif
2020-10-02 21:52:56 -03:00
2021-09-10 03:28:21 -03:00
int32_t demanded_pitch = nav_pitch_cd + g . pitch_trim_cd + 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 ;
2021-05-18 00:44:57 -03:00
}
2021-11-20 20:03:18 -04:00
/* force landing pitch if:
- flare switch high
- throttle stick at zero thrust
- in fixed wing non auto - throttle mode
*/
2021-09-10 03:28:21 -03:00
if ( ! quadplane_in_transition & &
! control_mode - > is_vtol_mode ( ) & &
! control_mode - > does_auto_throttle ( ) & &
2021-11-20 20:03:18 -04:00
flare_mode = = FlareMode : : ENABLED_PITCH_TARGET & &
throttle_at_zero ( ) ) {
2021-09-10 03:28:21 -03:00
demanded_pitch = landing . get_pitch_cd ( ) ;
}
2021-10-29 07:37:52 -03:00
return pitchController . get_servo_out ( demanded_pitch - ahrs . pitch_sensor , speed_scaler , disable_integrator ,
2023-04-26 00:27:13 -03:00
ground_mode & & ! ( plane . flight_option_enabled ( FlightOptions : : DISABLE_GROUND_PID_SUPPRESSION ) ) ) ;
2012-12-04 02:32:37 -04:00
}
2011-09-08 22:29:39 -03:00
2012-12-04 02:32:37 -04:00
/*
2023-01-29 22:52:19 -04:00
this gives the user control of the aircraft in stabilization modes , only used in Stabilize Mode
2023-04-24 21:31:04 -03:00
to be moved to mode_stabilize . cpp in future
2012-12-04 02:32:37 -04:00
*/
2023-04-24 21:31:04 -03:00
void ModeStabilize : : stabilize_stick_mixing_direct ( )
2012-12-04 02:32:37 -04:00
{
2023-04-24 21:31:04 -03:00
if ( ! plane . stick_mixing_enabled ( ) ) {
2012-12-04 02:32:37 -04:00
return ;
}
2023-04-15 21:18:05 -03:00
# if HAL_QUADPLANE_ENABLED
2023-04-24 21:31:04 -03:00
if ( ! plane . quadplane . allow_stick_mixing ( ) ) {
2023-04-15 21:18:05 -03:00
return ;
}
# endif
2021-09-18 15:02:12 -03:00
float aileron = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_aileron ) ;
2023-04-24 21:31:04 -03:00
aileron = plane . channel_roll - > stick_mixing ( aileron ) ;
2016-10-22 07:27:57 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_aileron , aileron ) ;
2021-09-18 15:02:12 -03:00
float elevator = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_elevator ) ;
2023-04-24 21:31:04 -03:00
elevator = plane . channel_pitch - > stick_mixing ( elevator ) ;
2016-10-22 07:27:57 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_elevator , elevator ) ;
2012-12-04 02:32:37 -04:00
}
2013-04-01 18:52:56 -03:00
/*
this gives the user control of the aircraft in stabilization modes
using FBW style controls
*/
2015-05-13 03:09:36 -03:00
void Plane : : stabilize_stick_mixing_fbw ( )
2013-04-01 18:52:56 -03:00
{
if ( ! stick_mixing_enabled ( ) | |
2019-01-15 13:46:13 -04:00
control_mode = = & mode_acro | |
control_mode = = & mode_fbwa | |
control_mode = = & mode_autotune | |
control_mode = = & mode_fbwb | |
control_mode = = & mode_cruise | |
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2019-01-15 13:46:13 -04:00
control_mode = = & mode_qstabilize | |
control_mode = = & mode_qhover | |
control_mode = = & mode_qloiter | |
control_mode = = & mode_qland | |
control_mode = = & mode_qacro | |
2021-09-10 03:28:21 -03:00
# if QAUTOTUNE_ENABLED
control_mode = = & mode_qautotune | |
# endif
2023-04-15 21:18:05 -03:00
! quadplane . allow_stick_mixing ( ) | |
2021-09-10 03:28:21 -03:00
# endif // HAL_QUADPLANE_ENABLED
control_mode = = & mode_training ) {
2013-04-01 18:52:56 -03:00
return ;
}
// do FBW style stick mixing. We don't treat it linearly
// however. For inputs up to half the maximum, we use linear
// addition to the nav_roll and nav_pitch. Above that it goes
// non-linear and ends up as 2x the maximum, to ensure that
// the user can direct the plane in any direction with stick
// mixing.
2023-09-04 18:30:27 -03:00
float roll_input = channel_roll - > norm_input_dz ( ) ;
2013-05-26 19:24:35 -03:00
if ( roll_input > 0.5f ) {
2013-04-01 18:52:56 -03:00
roll_input = ( 3 * roll_input - 1 ) ;
2013-05-26 19:24:35 -03:00
} else if ( roll_input < - 0.5f ) {
roll_input = ( 3 * roll_input + 1 ) ;
2013-04-01 18:52:56 -03:00
}
2013-11-04 04:48:22 -04:00
nav_roll_cd + = roll_input * roll_limit_cd ;
nav_roll_cd = constrain_int32 ( nav_roll_cd , - roll_limit_cd , roll_limit_cd ) ;
2022-05-10 09:53:10 -03:00
2023-04-26 00:27:13 -03:00
if ( ( control_mode = = & mode_loiter ) & & ( plane . flight_option_enabled ( FlightOptions : : ENABLE_LOITER_ALT_CONTROL ) ) ) {
2022-05-10 09:53:10 -03:00
// loiter is using altitude control based on the pitch stick, don't use it again here
return ;
}
2023-09-04 18:30:27 -03:00
float pitch_input = channel_pitch - > norm_input_dz ( ) ;
2016-06-01 19:07:55 -03:00
if ( pitch_input > 0.5f ) {
2013-04-01 18:52:56 -03:00
pitch_input = ( 3 * pitch_input - 1 ) ;
2016-06-01 19:07:55 -03:00
} else if ( pitch_input < - 0.5f ) {
pitch_input = ( 3 * pitch_input + 1 ) ;
2013-04-01 18:52:56 -03:00
}
2014-06-05 03:12:10 -03:00
if ( fly_inverted ( ) ) {
2013-04-01 18:52:56 -03:00
pitch_input = - pitch_input ;
}
if ( pitch_input > 0 ) {
2013-06-26 07:48:45 -03:00
nav_pitch_cd + = pitch_input * aparm . pitch_limit_max_cd ;
2013-04-01 18:52:56 -03:00
} else {
2013-11-04 04:48:22 -04:00
nav_pitch_cd + = - ( pitch_input * pitch_limit_min_cd ) ;
2013-04-01 18:52:56 -03:00
}
2013-11-04 04:48:22 -04:00
nav_pitch_cd = constrain_int32 ( nav_pitch_cd , pitch_limit_min_cd , aparm . pitch_limit_max_cd . get ( ) ) ;
2013-04-01 18:52:56 -03:00
}
2012-08-21 23:19:50 -03:00
2012-12-04 02:32:37 -04:00
/*
2013-10-03 09:01:43 -03:00
stabilize the yaw axis . There are 3 modes of operation :
- hold a specific heading with ground steering
- rate controlled with ground steering
- yaw control for coordinated flight
2012-12-04 02:32:37 -04:00
*/
2023-02-01 07:17:27 -04:00
void Plane : : stabilize_yaw ( )
2012-12-04 02:32:37 -04:00
{
2023-07-05 20:01:16 -03:00
bool ground_steering = false ;
2017-01-10 03:42:57 -04:00
if ( landing . is_flaring ( ) ) {
// in flaring then enable ground steering
2023-07-05 20:01:16 -03:00
ground_steering = true ;
2014-08-26 06:37:36 -03:00
} else {
// otherwise use ground steering when no input control and we
// are below the GROUND_STEER_ALT
2023-07-05 20:01:16 -03:00
ground_steering = ( channel_roll - > get_control_in ( ) = = 0 & &
2017-01-30 15:48:22 -04:00
fabsf ( relative_altitude ) < g . ground_steer_alt ) ;
2017-02-14 15:13:11 -04:00
if ( ! landing . is_ground_steering_allowed ( ) ) {
2014-08-28 22:36:09 -03:00
// don't use ground steering on landing approach
2023-07-05 20:01:16 -03:00
ground_steering = false ;
2014-08-28 22:36:09 -03:00
}
2014-08-26 06:37:36 -03:00
}
2012-12-04 02:32:37 -04:00
2014-03-04 21:13:19 -04:00
/*
2023-07-05 20:01:16 -03:00
first calculate steering for a nose or tail
2017-01-10 03:42:57 -04:00
wheel . We use " course hold " mode for the rudder when either performing
a flare ( when the wings are held level ) or when in course hold in
FBWA mode ( when we are below GROUND_STEER_ALT )
2014-03-04 21:13:19 -04:00
*/
2023-07-05 20:01:16 -03:00
float steering_output = 0.0 ;
2017-01-10 03:42:57 -04:00
if ( landing . is_flaring ( ) | |
2023-07-05 20:01:16 -03:00
( steer_state . hold_course_cd ! = - 1 & & ground_steering ) ) {
steering_output = calc_nav_yaw_course ( ) ;
} else if ( ground_steering ) {
steering_output = calc_nav_yaw_ground ( ) ;
2013-10-03 09:01:43 -03:00
}
2014-03-04 21:13:19 -04:00
/*
2023-07-05 20:01:16 -03:00
now calculate rudder for the rudder
2014-03-04 21:13:19 -04:00
*/
2023-07-05 20:01:16 -03:00
const float rudder_output = calc_nav_yaw_coordinated ( ) ;
if ( ! ground_steering ) {
// Not doing ground steering, output rudder on steering channel
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 ) ) {
// Ground steering active but no steering output configured, output steering on rudder channel
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_rudder , steering_output ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_steering , steering_output ) ;
} else {
// Ground steering with both steering and rudder channels
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_rudder , rudder_output ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_steering , steering_output ) ;
}
2011-09-08 22:29:39 -03:00
}
2012-12-04 02:32:37 -04:00
/*
main stabilization function for all 3 axes
*/
2015-05-13 03:09:36 -03:00
void Plane : : stabilize ( )
2012-12-04 02:32:37 -04:00
{
2020-10-30 20:26:00 -03:00
uint32_t now = AP_HAL : : millis ( ) ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-09-17 20:26:11 -03:00
if ( quadplane . available ( ) ) {
2023-04-15 21:18:05 -03:00
quadplane . transition - > set_FW_roll_pitch ( nav_pitch_cd , nav_roll_cd ) ;
2017-10-30 01:19:38 -03:00
}
2021-09-10 03:28:21 -03:00
# endif
2019-07-06 21:16:47 -03:00
if ( now - last_stabilize_ms > 2000 ) {
2023-04-24 09:28:55 -03:00
// if we haven't run the rate controllers for 2 seconds then reset
control_mode - > reset_controllers ( ) ;
2019-07-06 21:16:47 -03:00
}
last_stabilize_ms = now ;
2023-04-24 09:28:55 -03:00
if ( control_mode = = & mode_training | |
control_mode = = & mode_manual ) {
2023-02-12 09:38:37 -04:00
plane . control_mode - > run ( ) ;
2022-02-06 22:23:17 -04:00
# if AP_SCRIPTING_ENABLED
2022-10-26 19:50:10 -03:00
} else if ( nav_scripting_active ( ) ) {
2022-02-06 22:23:17 -04:00
// scripting is in control of roll and pitch rates and throttle
2023-02-01 07:17:27 -04:00
const float speed_scaler = get_speed_scaler ( ) ;
2022-02-06 22:23:17 -04:00
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 ) ;
2023-07-05 20:01:16 -03:00
float rudder = 0 ;
2022-02-06 22:23:17 -04:00
if ( yawController . rate_control_enabled ( ) ) {
2023-07-05 20:01:16 -03:00
rudder = nav_scripting . rudder_offset_pct * 45 ;
2022-12-22 17:21:59 -04:00
if ( nav_scripting . run_yaw_rate_controller ) {
rudder + = yawController . get_rate_out ( nav_scripting . yaw_rate_dps , speed_scaler , false ) ;
} else {
yawController . reset_I ( ) ;
}
2022-02-06 22:23:17 -04:00
}
2023-07-05 20:01:16 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_rudder , rudder ) ;
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_steering , rudder ) ;
2021-09-10 03:28:21 -03:00
# endif
2012-12-04 02:32:37 -04:00
} else {
2023-04-24 21:39:34 -03:00
plane . control_mode - > run ( ) ;
2012-12-04 02:32:37 -04:00
}
2013-06-01 04:34:40 -03:00
/*
see if we should zero the attitude controller integrators .
*/
2021-09-18 15:03:54 -03:00
if ( is_zero ( get_throttle_input ( ) ) & &
2017-01-30 15:48:22 -04:00
fabsf ( relative_altitude ) < 5.0f & &
2014-07-08 07:26:07 -03:00
fabsf ( barometer . get_climb_rate ( ) ) < 0.5f & &
2021-02-20 16:56:29 -04:00
ahrs . groundspeed ( ) < 3 ) {
2013-06-01 04:34:40 -03:00
// we are low, with no climb rate, and zero throttle, and very
// low ground speed. Zero the attitude controller
// integrators. This prevents integrator buildup pre-takeoff.
2013-08-14 01:57:41 -03:00
rollController . reset_I ( ) ;
pitchController . reset_I ( ) ;
yawController . reset_I ( ) ;
2014-08-24 19:20:37 -03:00
// if moving very slowly also zero the steering integrator
2021-02-20 16:56:29 -04:00
if ( ahrs . groundspeed ( ) < 1 ) {
2014-08-24 19:20:37 -03:00
steerController . reset_I ( ) ;
}
2013-06-01 04:34:40 -03:00
}
2012-12-04 02:32:37 -04:00
}
2015-05-13 03:09:36 -03:00
void Plane : : calc_throttle ( )
2011-09-08 22:29:39 -03:00
{
2013-06-26 07:48:45 -03:00
if ( aparm . throttle_cruise < = 1 ) {
2013-03-07 23:59:19 -04:00
// user has asked for zero throttle - this may be done by a
// mission which wants to turn off the engine for a parachute
// landing
2021-09-18 15:02:12 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_throttle , 0.0 ) ;
2013-03-07 23:59:19 -04:00
return ;
}
2021-11-12 13:53:28 -04:00
float commanded_throttle = TECS_controller . get_throttle_demand ( ) ;
2016-10-22 07:27:57 -03:00
SRV_Channels : : set_output_scaled ( SRV_Channel : : k_throttle , commanded_throttle ) ;
2011-09-08 22:29:39 -03:00
}
/*****************************************
2012-08-21 23:19:50 -03:00
* Calculate desired roll / pitch / yaw angles ( in medium freq loop )
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2011-09-08 22:29:39 -03:00
2013-10-03 09:01:43 -03:00
/*
calculate yaw control for coordinated flight
*/
2023-07-05 20:01:16 -03:00
int16_t Plane : : calc_nav_yaw_coordinated ( )
2011-09-08 22:29:39 -03:00
{
2023-02-01 07:17:27 -04:00
const float speed_scaler = get_speed_scaler ( ) ;
2013-08-02 08:55:34 -03:00
bool disable_integrator = false ;
2018-08-20 21:38:41 -03:00
int16_t rudder_in = rudder_input ( ) ;
2012-08-14 22:19:12 -03:00
2016-06-30 12:50:17 -03:00
int16_t commanded_rudder ;
2022-10-18 04:52:30 -03:00
bool using_rate_controller = false ;
2016-06-30 12:50:17 -03:00
// Received an external msg that guides yaw in the last 3 seconds?
2020-09-22 14:00:39 -03:00
if ( control_mode - > is_guided_mode ( ) & &
2016-06-30 12:50:17 -03:00
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 ;
2023-01-26 16:59:58 -04:00
} else if ( autotuning & & g . acro_yaw_rate > 0 & & yawController . rate_control_enabled ( ) ) {
2021-11-25 04:42:08 -04:00
// user is doing an AUTOTUNE with yaw rate control
const float rudd_expo = rudder_in_expo ( true ) ;
const float yaw_rate = ( rudd_expo / SERVO_MAX ) * g . acro_yaw_rate ;
2023-10-11 04:41:54 -03:00
// add in the coordinated turn yaw rate to make it easier to fly while tuning the yaw rate controller
2022-11-29 00:49:36 -04:00
const float coordination_yaw_rate = degrees ( GRAVITY_MSS * tanf ( radians ( nav_roll_cd * 0.01f ) ) / MAX ( aparm . airspeed_min , smoothed_airspeed ) ) ;
commanded_rudder = yawController . get_rate_out ( yaw_rate + coordination_yaw_rate , speed_scaler , false ) ;
2022-10-18 04:52:30 -03:00
using_rate_controller = true ;
2016-06-30 12:50:17 -03:00
} else {
2019-01-15 13:46:13 -04:00
if ( control_mode = = & mode_stabilize & & rudder_in ! = 0 ) {
2018-08-20 21:38:41 -03:00
disable_integrator = true ;
}
2016-06-30 12:50:17 -03:00
commanded_rudder = yawController . get_servo_out ( speed_scaler , disable_integrator ) ;
// add in rudder mixing from roll
2016-10-22 07:27:57 -03:00
commanded_rudder + = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_aileron ) * g . kff_rudder_mix ;
2018-08-20 21:38:41 -03:00
commanded_rudder + = rudder_in ;
2016-06-30 12:50:17 -03:00
}
2022-10-18 04:52:30 -03:00
if ( ! using_rate_controller ) {
/*
When not running the yaw rate controller , we need to reset the rate
*/
yawController . reset_rate_PID ( ) ;
}
2023-07-05 20:01:16 -03:00
return constrain_int16 ( commanded_rudder , - 4500 , 4500 ) ;
2011-09-08 22:29:39 -03:00
}
2013-10-03 09:01:43 -03:00
/*
calculate yaw control for ground steering with specific course
*/
2023-07-05 20:01:16 -03:00
int16_t Plane : : calc_nav_yaw_course ( void )
2013-10-03 09:01:43 -03:00
{
// holding a specific navigation course on the ground. Used in
// auto-takeoff and landing
int32_t bearing_error_cd = nav_controller - > bearing_error_cd ( ) ;
2023-07-05 20:01:16 -03:00
int16_t steering = steerController . get_steering_out_angle_error ( bearing_error_cd ) ;
2013-10-03 09:01:43 -03:00
if ( stick_mixing_enabled ( ) ) {
2023-07-05 20:01:16 -03:00
steering = channel_rudder - > stick_mixing ( steering ) ;
2013-10-03 09:01:43 -03:00
}
2023-07-05 20:01:16 -03:00
return constrain_int16 ( steering , - 4500 , 4500 ) ;
2013-10-03 09:01:43 -03:00
}
/*
calculate yaw control for ground steering
*/
2023-07-05 20:01:16 -03:00
int16_t Plane : : calc_nav_yaw_ground ( void )
2013-10-03 09:01:43 -03:00
{
2014-03-28 16:52:48 -03:00
if ( gps . ground_speed ( ) < 1 & &
2021-09-18 15:03:54 -03:00
is_zero ( get_throttle_input ( ) ) & &
2022-09-29 20:10:41 -03:00
flight_stage ! = AP_FixedWing : : FlightStage : : TAKEOFF & &
flight_stage ! = AP_FixedWing : : FlightStage : : ABORT_LANDING ) {
2013-10-03 09:16:09 -03:00
// manual rudder control while still
steer_state . locked_course = false ;
steer_state . locked_course_err = 0 ;
2023-07-05 20:01:16 -03:00
return rudder_input ( ) ;
2013-10-03 09:16:09 -03:00
}
2021-12-03 03:27:16 -04:00
// if we haven't been steering for 1s then clear locked course
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 ;
2018-08-20 21:38:41 -03:00
float steer_rate = ( rudder_input ( ) / 4500.0f ) * g . ground_steer_dps ;
2022-09-29 20:10:41 -03:00
if ( flight_stage = = AP_FixedWing : : FlightStage : : TAKEOFF | |
flight_stage = = AP_FixedWing : : FlightStage : : ABORT_LANDING ) {
2014-10-06 17:17:33 -03:00
steer_rate = 0 ;
}
2015-05-04 23:34:27 -03:00
if ( ! is_zero ( steer_rate ) ) {
2013-10-03 09:01:43 -03:00
// pilot is giving rudder input
steer_state . locked_course = false ;
2013-10-03 09:16:09 -03:00
} else if ( ! steer_state . locked_course ) {
2013-10-03 09:01:43 -03:00
// pilot has released the rudder stick or we are still - lock the course
steer_state . locked_course = true ;
2022-09-29 20:10:41 -03:00
if ( flight_stage ! = AP_FixedWing : : FlightStage : : TAKEOFF & &
flight_stage ! = AP_FixedWing : : FlightStage : : ABORT_LANDING ) {
2014-10-06 17:17:33 -03:00
steer_state . locked_course_err = 0 ;
}
2013-10-03 09:01:43 -03:00
}
2021-12-03 03:27:16 -04:00
2023-07-05 20:01:16 -03:00
int16_t steering ;
2013-10-03 09:01:43 -03:00
if ( ! steer_state . locked_course ) {
2013-10-03 09:51:43 -03:00
// use a rate controller at the pilot specified rate
2023-07-05 20:01:16 -03:00
steering = steerController . get_steering_out_rate ( steer_rate ) ;
2013-10-03 09:01:43 -03:00
} else {
2013-10-03 09:51:43 -03:00
// use a error controller on the summed error
2013-10-03 09:01:43 -03:00
int32_t yaw_error_cd = - ToDeg ( steer_state . locked_course_err ) * 100 ;
2023-07-05 20:01:16 -03:00
steering = steerController . get_steering_out_angle_error ( yaw_error_cd ) ;
2013-10-03 09:01:43 -03:00
}
2023-07-05 20:01:16 -03:00
return constrain_int16 ( steering , - 4500 , 4500 ) ;
2013-10-03 09:01:43 -03:00
}
2011-09-08 22:29:39 -03:00
2014-11-11 22:35:34 -04:00
/*
calculate a new nav_pitch_cd from the speed height controller
*/
2015-05-13 03:09:36 -03:00
void Plane : : calc_nav_pitch ( )
2011-09-08 22:29:39 -03:00
{
2021-11-12 13:53:28 -04:00
int32_t commanded_pitch = TECS_controller . get_pitch_demand ( ) ;
2016-06-30 12:50:17 -03:00
nav_pitch_cd = constrain_int32 ( commanded_pitch , pitch_limit_min_cd , aparm . pitch_limit_max_cd . get ( ) ) ;
2011-09-08 22:29:39 -03:00
}
2014-11-11 22:35:34 -04:00
/*
calculate a new nav_roll_cd from the navigation controller
*/
2015-05-13 03:09:36 -03:00
void Plane : : calc_nav_roll ( )
2011-09-08 22:29:39 -03:00
{
2016-05-09 11:34:11 -03:00
int32_t commanded_roll = nav_controller - > nav_roll_cd ( ) ;
nav_roll_cd = constrain_int32 ( commanded_roll , - roll_limit_cd , roll_limit_cd ) ;
2014-11-11 22:35:34 -04:00
update_load_factor ( ) ;
2011-09-08 22:29:39 -03:00
}
2014-08-03 04:16:51 -03:00
/*
adjust nav_pitch_cd for STAB_PITCH_DOWN_CD . This is used to make
keeping up good airspeed in FBWA mode easier , as the plane will
automatically pitch down a little when at low throttle . It makes
FBWA landings without stalling much easier .
*/
2015-05-13 03:09:36 -03:00
void Plane : : adjust_nav_pitch_throttle ( void )
2014-08-03 04:16:51 -03:00
{
2016-01-30 02:38:31 -04:00
int8_t throttle = throttle_percentage ( ) ;
2022-09-29 20:10:41 -03:00
if ( throttle > = 0 & & throttle < aparm . throttle_cruise & & flight_stage ! = AP_FixedWing : : FlightStage : : VTOL ) {
2014-08-03 04:16:51 -03:00
float p = ( aparm . throttle_cruise - throttle ) / ( float ) aparm . throttle_cruise ;
2014-08-05 22:46:40 -03:00
nav_pitch_cd - = g . stab_pitch_down * 100.0f * p ;
2014-08-03 04:16:51 -03:00
}
}
2014-11-11 22:35:34 -04:00
/*
calculate a new aerodynamic_load_factor and limit nav_roll_cd to
ensure that the load factor does not take us below the sustainable
airspeed
*/
2015-05-13 03:09:36 -03:00
void Plane : : update_load_factor ( void )
2014-11-11 22:35:34 -04:00
{
float demanded_roll = fabsf ( nav_roll_cd * 0.01f ) ;
if ( demanded_roll > 85 ) {
// limit to 85 degrees to prevent numerical errors
demanded_roll = 85 ;
}
2015-05-15 12:54:46 -03:00
aerodynamic_load_factor = 1.0f / safe_sqrt ( cosf ( radians ( demanded_roll ) ) ) ;
2014-11-11 22:35:34 -04:00
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-09-17 20:26:11 -03:00
if ( quadplane . available ( ) & & quadplane . transition - > set_FW_roll_limit ( roll_limit_cd ) ) {
2018-12-30 18:46:14 -04:00
nav_roll_cd = constrain_int32 ( nav_roll_cd , - roll_limit_cd , roll_limit_cd ) ;
return ;
2017-10-29 03:31:09 -03:00
}
2021-09-10 03:28:21 -03:00
# endif
2014-11-12 23:06:00 -04:00
if ( ! aparm . stall_prevention ) {
// stall prevention is disabled
return ;
}
if ( fly_inverted ( ) ) {
// no roll limits when inverted
return ;
}
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-07-14 17:15:49 -03:00
if ( quadplane . tailsitter . active ( ) ) {
2017-02-11 04:12:56 -04:00
// no limits while hovering
return ;
}
2021-09-10 03:28:21 -03:00
# endif
2014-11-12 23:06:00 -04:00
2017-11-19 01:04:40 -04:00
float max_load_factor = smoothed_airspeed / MAX ( aparm . airspeed_min , 1 ) ;
2014-11-11 22:35:34 -04:00
if ( max_load_factor < = 1 ) {
// our airspeed is below the minimum airspeed. Limit roll to
// 25 degrees
nav_roll_cd = constrain_int32 ( nav_roll_cd , - 2500 , 2500 ) ;
2018-12-26 18:36:12 -04:00
roll_limit_cd = MIN ( roll_limit_cd , 2500 ) ;
2014-11-11 22:35:34 -04:00
} else if ( max_load_factor < aerodynamic_load_factor ) {
2023-10-11 04:41:54 -03:00
// the demanded nav_roll would take us past the aerodynamic
2014-11-11 22:35:34 -04:00
// load limit. Limit our roll to a bank angle that will keep
// the load within what the airframe can handle. We always
// allow at least 25 degrees of roll however, to ensure the
2023-10-11 04:41:54 -03:00
// aircraft can be manoeuvred with a bad airspeed estimate. At
2014-11-11 22:35:34 -04:00
// 25 degrees the load factor is 1.1 (10%)
int32_t roll_limit = degrees ( acosf ( sq ( 1.0f / max_load_factor ) ) ) * 100 ;
if ( roll_limit < 2500 ) {
roll_limit = 2500 ;
}
nav_roll_cd = constrain_int32 ( nav_roll_cd , - roll_limit , roll_limit ) ;
2018-12-26 18:36:12 -04:00
roll_limit_cd = MIN ( roll_limit_cd , roll_limit ) ;
2014-11-11 22:35:34 -04:00
}
}