2017-02-07 20:49:33 -04:00
# include "AC_AttitudeControl_Sub.h"
# include <AP_HAL/AP_HAL.h>
# include <AP_Math/AP_Math.h>
// table of user settable parameters
const AP_Param : : GroupInfo AC_AttitudeControl_Sub : : var_info [ ] = {
// parameters from parent vehicle
AP_NESTEDGROUPINFO ( AC_AttitudeControl , 0 ) ,
// @Param: RAT_RLL_P
// @DisplayName: Roll axis rate controller P gain
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.30
2017-02-07 20:49:33 -04:00
// @Increment: 0.005
// @User: Standard
// @Param: RAT_RLL_I
// @DisplayName: Roll axis rate controller I gain
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.5
2017-02-07 20:49:33 -04:00
// @Increment: 0.01
// @User: Standard
// @Param: RAT_RLL_IMAX
// @DisplayName: Roll axis rate controller I gain maximum
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
2017-05-02 10:37:20 -03:00
// @Units: %
2017-02-07 20:49:33 -04:00
// @User: Standard
// @Param: RAT_RLL_D
// @DisplayName: Roll axis rate controller D gain
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
// @Range: 0.0 0.02
// @Increment: 0.001
// @User: Standard
2017-03-01 01:59:30 -04:00
// @Param: RAT_RLL_FF
// @DisplayName: Roll axis rate controller feed forward
// @Description: Roll axis rate controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
2019-07-16 03:02:58 -03:00
// @Param: RAT_RLL_FLTT
// @DisplayName: Roll axis rate controller input frequency in Hz
// @Description: Roll axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_RLL_FLTE
// @DisplayName: Roll axis rate controller input frequency in Hz
// @Description: Roll axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_RLL_FLTD
2017-02-07 20:49:33 -04:00
// @DisplayName: Roll axis rate controller input frequency in Hz
// @Description: Roll axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
AP_SUBGROUPINFO ( _pid_rate_roll , " RAT_RLL_ " , 1 , AC_AttitudeControl_Sub , AC_PID ) ,
// @Param: RAT_PIT_P
// @DisplayName: Pitch axis rate controller P gain
// @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.30
2017-02-07 20:49:33 -04:00
// @Increment: 0.005
// @User: Standard
// @Param: RAT_PIT_I
// @DisplayName: Pitch axis rate controller I gain
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.5
2017-02-07 20:49:33 -04:00
// @Increment: 0.01
// @User: Standard
// @Param: RAT_PIT_IMAX
// @DisplayName: Pitch axis rate controller I gain maximum
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
2017-05-02 10:37:20 -03:00
// @Units: %
2017-02-07 20:49:33 -04:00
// @User: Standard
// @Param: RAT_PIT_D
// @DisplayName: Pitch axis rate controller D gain
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
// @Range: 0.0 0.02
// @Increment: 0.001
// @User: Standard
2017-03-01 01:59:30 -04:00
// @Param: RAT_PIT_FF
// @DisplayName: Pitch axis rate controller feed forward
// @Description: Pitch axis rate controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
2019-07-16 03:02:58 -03:00
// @Param: RAT_PIT_FLTT
// @DisplayName: Pitch axis rate controller input frequency in Hz
// @Description: Pitch axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_PIT_FLTE
// @DisplayName: Pitch axis rate controller input frequency in Hz
// @Description: Pitch axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_PIT_FLTD
2017-02-07 20:49:33 -04:00
// @DisplayName: Pitch axis rate controller input frequency in Hz
// @Description: Pitch axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
AP_SUBGROUPINFO ( _pid_rate_pitch , " RAT_PIT_ " , 2 , AC_AttitudeControl_Sub , AC_PID ) ,
// @Param: RAT_YAW_P
// @DisplayName: Yaw axis rate controller P gain
// @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.50
2017-02-07 20:49:33 -04:00
// @Increment: 0.005
// @User: Standard
// @Param: RAT_YAW_I
// @DisplayName: Yaw axis rate controller I gain
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
2018-04-11 20:25:52 -03:00
// @Range: 0.0 0.05
2017-02-07 20:49:33 -04:00
// @Increment: 0.01
// @User: Standard
// @Param: RAT_YAW_IMAX
// @DisplayName: Yaw axis rate controller I gain maximum
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
2017-05-02 10:37:20 -03:00
// @Units: %
2017-02-07 20:49:33 -04:00
// @User: Standard
// @Param: RAT_YAW_D
// @DisplayName: Yaw axis rate controller D gain
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
// @Range: 0.000 0.02
// @Increment: 0.001
2017-03-01 01:59:30 -04:00
// @User: Standard
// @Param: RAT_YAW_FF
// @DisplayName: Yaw axis rate controller feed forward
// @Description: Yaw axis rate controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
2017-02-07 20:49:33 -04:00
// @User: Standard
2019-07-16 03:02:58 -03:00
// @Param: RAT_YAW_FLTT
// @DisplayName: Yaw axis rate controller input frequency in Hz
// @Description: Yaw axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_YAW_FLTE
// @DisplayName: Yaw axis rate controller input frequency in Hz
// @Description: Yaw axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_YAW_FLTD
2017-02-07 20:49:33 -04:00
// @DisplayName: Yaw axis rate controller input frequency in Hz
// @Description: Yaw axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
AP_SUBGROUPINFO ( _pid_rate_yaw , " RAT_YAW_ " , 3 , AC_AttitudeControl_Sub , AC_PID ) ,
// @Param: THR_MIX_MIN
// @DisplayName: Throttle Mix Minimum
// @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
// @Range: 0.1 0.25
// @User: Advanced
AP_GROUPINFO ( " THR_MIX_MIN " , 4 , AC_AttitudeControl_Sub , _thr_mix_min , AC_ATTITUDE_CONTROL_MIN_DEFAULT ) ,
// @Param: THR_MIX_MAX
// @DisplayName: Throttle Mix Maximum
// @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
// @Range: 0.5 0.9
// @User: Advanced
AP_GROUPINFO ( " THR_MIX_MAX " , 5 , AC_AttitudeControl_Sub , _thr_mix_max , AC_ATTITUDE_CONTROL_MAX_DEFAULT ) ,
// @Param: THR_MIX_MAN
// @DisplayName: Throttle Mix Manual
// @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
// @Range: 0.5 0.9
// @User: Advanced
AP_GROUPINFO ( " THR_MIX_MAN " , 6 , AC_AttitudeControl_Sub , _thr_mix_man , AC_ATTITUDE_CONTROL_MAN_DEFAULT ) ,
2019-07-16 03:02:58 -03:00
// @Param: RAT_RLL_FILT
// @DisplayName: Roll axis rate controller input frequency in Hz
// @Description: Roll axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_PIT_FILT
// @DisplayName: Pitch axis rate controller input frequency in Hz
// @Description: Pitch axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_YAW_FILT
// @DisplayName: Yaw axis rate controller input frequency in Hz
// @Description: Yaw axis rate controller input frequency in Hz
// @Range: 1 100
// @Increment: 1
// @Units: Hz
// @User: Standard
2017-02-07 20:49:33 -04:00
AP_GROUPEND
} ;
AC_AttitudeControl_Sub : : AC_AttitudeControl_Sub ( AP_AHRS_View & ahrs , const AP_Vehicle : : MultiCopter & aparm , AP_MotorsMulticopter & motors , float dt ) :
AC_AttitudeControl ( ahrs , aparm , motors , dt ) ,
_motors_multi ( motors ) ,
2019-07-16 03:02:58 -03:00
_pid_rate_roll ( AC_ATC_SUB_RATE_RP_P , AC_ATC_SUB_RATE_RP_I , AC_ATC_SUB_RATE_RP_D , 0.0f , AC_ATC_SUB_RATE_RP_IMAX , AC_ATC_SUB_RATE_RP_FILT_HZ , 0.0f , AC_ATC_SUB_RATE_RP_FILT_HZ , dt ) ,
_pid_rate_pitch ( AC_ATC_SUB_RATE_RP_P , AC_ATC_SUB_RATE_RP_I , AC_ATC_SUB_RATE_RP_D , 0.0f , AC_ATC_SUB_RATE_RP_IMAX , AC_ATC_SUB_RATE_RP_FILT_HZ , 0.0f , AC_ATC_SUB_RATE_RP_FILT_HZ , dt ) ,
_pid_rate_yaw ( AC_ATC_SUB_RATE_YAW_P , AC_ATC_SUB_RATE_YAW_I , AC_ATC_SUB_RATE_YAW_D , 0.0f , AC_ATC_SUB_RATE_YAW_IMAX , AC_ATC_SUB_RATE_YAW_FILT_HZ , 0.0f , AC_ATC_SUB_RATE_YAW_FILT_HZ , dt )
2017-02-07 20:49:33 -04:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
// Sub-specific defaults for parent class
_p_angle_roll . kP ( ) . set_default ( AC_ATC_SUB_ANGLE_P ) ;
_p_angle_pitch . kP ( ) . set_default ( AC_ATC_SUB_ANGLE_P ) ;
_p_angle_yaw . kP ( ) . set_default ( AC_ATC_SUB_ANGLE_P ) ;
_accel_yaw_max . set_default ( AC_ATC_SUB_ACCEL_Y_MAX ) ;
}
// Update Alt_Hold angle maximum
void AC_AttitudeControl_Sub : : update_althold_lean_angle_max ( float throttle_in )
{
// calc maximum tilt angle based on throttle
float thr_max = _motors_multi . get_throttle_thrust_max ( ) ;
// divide by zero check
if ( is_zero ( thr_max ) ) {
_althold_lean_angle_max = 0.0f ;
return ;
}
2018-05-03 22:20:34 -03:00
float althold_lean_angle_max = acosf ( constrain_float ( _throttle_in / ( AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max ) , 0.0f , 1.0f ) ) ;
2017-02-07 20:49:33 -04:00
_althold_lean_angle_max = _althold_lean_angle_max + ( _dt / ( _dt + _angle_limit_tc ) ) * ( althold_lean_angle_max - _althold_lean_angle_max ) ;
}
void AC_AttitudeControl_Sub : : set_throttle_out ( float throttle_in , bool apply_angle_boost , float filter_cutoff )
{
_throttle_in = throttle_in ;
update_althold_lean_angle_max ( throttle_in ) ;
_motors . set_throttle_filter_cutoff ( filter_cutoff ) ;
if ( apply_angle_boost ) {
// Apply angle boost
throttle_in = get_throttle_boosted ( throttle_in ) ;
} else {
// Clear angle_boost for logging purposes
_angle_boost = 0.0f ;
}
_motors . set_throttle ( throttle_in ) ;
_motors . set_throttle_avg_max ( get_throttle_avg_max ( MAX ( throttle_in , _throttle_in ) ) ) ;
}
// returns a throttle including compensation for roll/pitch angle
// throttle value should be 0 ~ 1
float AC_AttitudeControl_Sub : : get_throttle_boosted ( float throttle_in )
{
if ( ! _angle_boost_enabled ) {
_angle_boost = 0 ;
return throttle_in ;
}
// inverted_factor is 1 for tilt angles below 60 degrees
// inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees
float cos_tilt = _ahrs . cos_pitch ( ) * _ahrs . cos_roll ( ) ;
float inverted_factor = constrain_float ( 2.0f * cos_tilt , 0.0f , 1.0f ) ;
float boost_factor = 1.0f / constrain_float ( cos_tilt , 0.5f , 1.0f ) ;
float throttle_out = throttle_in * inverted_factor * boost_factor ;
_angle_boost = constrain_float ( throttle_out - throttle_in , - 1.0f , 1.0f ) ;
return throttle_out ;
}
// returns a throttle including compensation for roll/pitch angle
// throttle value should be 0 ~ 1
float AC_AttitudeControl_Sub : : get_throttle_avg_max ( float throttle_in )
{
throttle_in = constrain_float ( throttle_in , 0.0f , 1.0f ) ;
return MAX ( throttle_in , throttle_in * MAX ( 0.0f , 1.0f - _throttle_rpy_mix ) + _motors . get_throttle_hover ( ) * _throttle_rpy_mix ) ;
}
// update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value
void AC_AttitudeControl_Sub : : update_throttle_rpy_mix ( )
{
// slew _throttle_rpy_mix to _throttle_rpy_mix_desired
if ( _throttle_rpy_mix < _throttle_rpy_mix_desired ) {
// increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)
_throttle_rpy_mix + = MIN ( 2.0f * _dt , _throttle_rpy_mix_desired - _throttle_rpy_mix ) ;
} else if ( _throttle_rpy_mix > _throttle_rpy_mix_desired ) {
// reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)
_throttle_rpy_mix - = MIN ( 0.5f * _dt , _throttle_rpy_mix - _throttle_rpy_mix_desired ) ;
}
_throttle_rpy_mix = constrain_float ( _throttle_rpy_mix , 0.1f , AC_ATTITUDE_CONTROL_MAX ) ;
}
void AC_AttitudeControl_Sub : : rate_controller_run ( )
{
// move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)
update_throttle_rpy_mix ( ) ;
2017-03-02 07:49:25 -04:00
Vector3f gyro_latest = _ahrs . get_gyro_latest ( ) ;
2019-07-27 02:37:50 -03:00
_motors . set_roll ( get_rate_roll_pid ( ) . update_all ( _rate_target_ang_vel . x , gyro_latest . x , _motors . limit . roll ) ) ;
_motors . set_pitch ( get_rate_pitch_pid ( ) . update_all ( _rate_target_ang_vel . y , gyro_latest . y , _motors . limit . pitch ) ) ;
2019-07-16 03:02:58 -03:00
_motors . set_yaw ( get_rate_yaw_pid ( ) . update_all ( _rate_target_ang_vel . z , gyro_latest . z , _motors . limit . yaw ) ) ;
2017-02-07 20:49:33 -04:00
control_monitor_update ( ) ;
}
// sanity check parameters. should be called once before takeoff
void AC_AttitudeControl_Sub : : parameter_sanity_check ( )
{
// sanity check throttle mix parameters
if ( _thr_mix_man < 0.1f | | _thr_mix_man > 4.0f ) {
// parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0
// which can be useful for very high powered copters with very low hover throttle
_thr_mix_man . set_and_save ( AC_ATTITUDE_CONTROL_MAN_DEFAULT ) ;
}
if ( _thr_mix_min < 0.1f | | _thr_mix_min > 0.25f ) {
_thr_mix_min . set_and_save ( AC_ATTITUDE_CONTROL_MIN_DEFAULT ) ;
}
if ( _thr_mix_max < 0.5f | | _thr_mix_max > AC_ATTITUDE_CONTROL_MAX ) {
// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0
// which can be useful for very high powered copters with very low hover throttle
_thr_mix_max . set_and_save ( AC_ATTITUDE_CONTROL_MAX_DEFAULT ) ;
}
if ( _thr_mix_min > _thr_mix_max ) {
_thr_mix_min . set_and_save ( AC_ATTITUDE_CONTROL_MIN_DEFAULT ) ;
_thr_mix_max . set_and_save ( AC_ATTITUDE_CONTROL_MAX_DEFAULT ) ;
}
}