2014-01-29 09:50:32 -04:00
# include "AC_AttitudeControl_Heli.h"
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
2014-01-29 09:50:32 -04:00
// table of user settable parameters
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AC_AttitudeControl_Heli : : var_info [ ] = {
2015-05-08 02:49:09 -03:00
// parameters from parent vehicle
AP_NESTEDGROUPINFO ( AC_AttitudeControl , 0 ) ,
2015-03-04 03:23:20 -04:00
2015-10-13 16:02:21 -03:00
// @Param: HOVR_ROL_TRM
// @DisplayName: Hover Roll Trim
// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
2017-05-02 10:37:20 -03:00
// @Units: cdeg
2021-05-20 10:08:46 -03:00
// @Increment: 10
2015-10-13 16:02:21 -03:00
// @Range: 0 1000
// @User: Advanced
AP_GROUPINFO ( " HOVR_ROL_TRM " , 1 , AC_AttitudeControl_Heli , _hover_roll_trim , AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT ) ,
2016-02-15 02:25:55 -04:00
// @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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.35
2016-02-15 02:25:55 -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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.6
2016-02-15 02:25:55 -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
2016-02-17 07:14:24 -04:00
// @Range: 0 1
// @Increment: 0.01
2016-02-15 02:25:55 -04:00
// @User: Standard
2020-02-13 05:17:01 -04:00
// @Param: RAT_RLL_ILMI
// @DisplayName: Roll axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
2016-02-15 02:25:55 -04:00
// @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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.03
2016-02-15 02:25:55 -04:00
// @Increment: 0.001
// @User: Standard
2022-02-01 19:47:45 -04:00
// @Param: RAT_RLL_FF
2017-03-01 01:59:30 -04:00
// @DisplayName: Roll axis rate controller feed forward
// @Description: Roll axis rate controller feed forward
2021-05-24 22:01:37 -03:00
// @Range: 0.05 0.5
2017-03-01 01:59:30 -04:00
// @Increment: 0.001
// @User: Standard
2020-01-19 11:08:46 -04:00
// @Param: RAT_RLL_FLTT
// @DisplayName: Roll axis rate controller target frequency in Hz
// @Description: Roll axis rate controller target frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
2016-02-17 22:10:34 -04:00
// @Units: Hz
2020-01-19 11:08:46 -04:00
// @User: Standard
// @Param: RAT_RLL_FLTE
// @DisplayName: Roll axis rate controller error frequency in Hz
// @Description: Roll axis rate controller error frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
// @Units: Hz
// @User: Standard
// @Param: RAT_RLL_FLTD
// @DisplayName: Roll axis rate controller derivative frequency in Hz
// @Description: Roll axis rate controller derivative frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 0 50
2016-02-17 07:14:24 -04:00
// @Increment: 1
2020-01-19 11:08:46 -04:00
// @Units: Hz
// @User: Standard
2020-09-24 04:26:05 -03:00
// @Param: RAT_RLL_SMAX
// @DisplayName: Roll slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
2016-02-15 02:25:55 -04:00
AP_SUBGROUPINFO ( _pid_rate_roll , " RAT_RLL_ " , 2 , AC_AttitudeControl_Heli , AC_HELI_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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.35
2016-02-15 02:25:55 -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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.6
2016-02-15 02:25:55 -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
2016-02-17 07:14:24 -04:00
// @Range: 0 1
// @Increment: 0.01
2016-02-15 02:25:55 -04:00
// @User: Standard
2020-02-13 05:17:01 -04:00
// @Param: RAT_PIT_ILMI
// @DisplayName: Pitch axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
2016-02-15 02:25:55 -04:00
// @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
2021-05-24 22:01:37 -03:00
// @Range: 0.0 0.03
2016-02-15 02:25:55 -04:00
// @Increment: 0.001
// @User: Standard
2022-02-01 19:47:45 -04:00
// @Param: RAT_PIT_FF
2017-03-01 01:59:30 -04:00
// @DisplayName: Pitch axis rate controller feed forward
// @Description: Pitch axis rate controller feed forward
2021-05-24 22:01:37 -03:00
// @Range: 0.05 0.5
2017-03-01 01:59:30 -04:00
// @Increment: 0.001
// @User: Standard
2020-01-19 11:08:46 -04:00
// @Param: RAT_PIT_FLTT
// @DisplayName: Pitch axis rate controller target frequency in Hz
// @Description: Pitch axis rate controller target frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
2016-02-17 22:10:34 -04:00
// @Units: Hz
2020-01-19 11:08:46 -04:00
// @User: Standard
// @Param: RAT_PIT_FLTE
// @DisplayName: Pitch axis rate controller error frequency in Hz
// @Description: Pitch axis rate controller error frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2016-02-17 07:14:24 -04:00
// @Increment: 1
2020-01-19 11:08:46 -04:00
// @Units: Hz
// @User: Standard
// @Param: RAT_PIT_FLTD
// @DisplayName: Pitch axis rate controller derivative frequency in Hz
// @Description: Pitch axis rate controller derivative frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 0 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
// @Units: Hz
// @User: Standard
2020-09-24 04:26:05 -03:00
// @Param: RAT_PIT_SMAX
// @DisplayName: Pitch slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
2016-02-15 02:25:55 -04:00
AP_SUBGROUPINFO ( _pid_rate_pitch , " RAT_PIT_ " , 3 , AC_AttitudeControl_Heli , AC_HELI_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
2016-02-17 07:14:24 -04:00
// @Range: 0.180 0.60
2016-02-15 02:25:55 -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
2021-05-24 22:01:37 -03:00
// @Range: 0.01 0.2
2016-02-15 02:25:55 -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
2016-02-17 07:14:24 -04:00
// @Range: 0 1
// @Increment: 0.01
2016-02-15 02:25:55 -04:00
// @User: Standard
2020-02-13 05:17:01 -04:00
// @Param: RAT_YAW_ILMI
// @DisplayName: Yaw axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
2016-02-15 02:25:55 -04:00
// @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
// @User: Standard
2022-02-01 19:47:45 -04:00
// @Param: RAT_YAW_FF
2017-03-01 01:59:30 -04:00
// @DisplayName: Yaw axis rate controller feed forward
// @Description: Yaw axis rate controller feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
2020-01-19 11:08:46 -04:00
// @Param: RAT_YAW_FLTT
// @DisplayName: Yaw axis rate controller target frequency in Hz
// @Description: Yaw axis rate controller target frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
2016-02-17 22:10:34 -04:00
// @Units: Hz
2020-01-19 11:08:46 -04:00
// @User: Standard
// @Param: RAT_YAW_FLTE
// @DisplayName: Yaw axis rate controller error frequency in Hz
// @Description: Yaw axis rate controller error frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 5 50
2016-02-17 07:14:24 -04:00
// @Increment: 1
2020-01-19 11:08:46 -04:00
// @Units: Hz
// @User: Standard
// @Param: RAT_YAW_FLTD
// @DisplayName: Yaw axis rate controller derivative frequency in Hz
// @Description: Yaw axis rate controller derivative frequency in Hz
2020-02-25 04:45:38 -04:00
// @Range: 0 50
2020-01-19 11:08:46 -04:00
// @Increment: 1
// @Units: Hz
// @User: Standard
2020-09-24 04:26:05 -03:00
// @Param: RAT_YAW_SMAX
// @DisplayName: Yaw slew rate limit
// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
// @Range: 0 200
// @Increment: 0.5
// @User: Advanced
2016-02-15 02:25:55 -04:00
AP_SUBGROUPINFO ( _pid_rate_yaw , " RAT_YAW_ " , 4 , AC_AttitudeControl_Heli , AC_HELI_PID ) ,
2017-08-10 03:15:18 -03:00
// @Param: PIRO_COMP
// @DisplayName: Piro Comp Enable
// @Description: Pirouette compensation enabled
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO ( " PIRO_COMP " , 5 , AC_AttitudeControl_Heli , _piro_comp_enabled , 0 ) ,
2014-01-29 09:50:32 -04:00
AP_GROUPEND
} ;
2014-08-20 10:14:25 -03:00
// passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode
2015-11-24 17:11:50 -04:00
void AC_AttitudeControl_Heli : : passthrough_bf_roll_pitch_rate_yaw ( float roll_passthrough , float pitch_passthrough , float yaw_rate_bf_cds )
2014-08-20 10:14:25 -03:00
{
2015-11-24 17:11:50 -04:00
// convert from centidegrees on public interface to radians
2019-07-16 03:03:22 -03:00
float yaw_rate_bf_rads = radians ( yaw_rate_bf_cds * 0.01f ) ;
2015-11-24 17:11:50 -04:00
2015-06-22 02:49:25 -03:00
// store roll, pitch and passthroughs
2015-11-24 17:11:50 -04:00
// NOTE: this abuses yaw_rate_bf_rads
2014-08-20 10:14:25 -03:00
_passthrough_roll = roll_passthrough ;
_passthrough_pitch = pitch_passthrough ;
2019-07-16 03:03:22 -03:00
_passthrough_yaw = degrees ( yaw_rate_bf_rads ) * 100.0f ;
2014-08-20 10:14:25 -03:00
// set rate controller to use pass through
_flags_heli . flybar_passthrough = true ;
// set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
2021-04-14 12:42:42 -03:00
_ang_vel_target . x = _ahrs . get_gyro ( ) . x ;
_ang_vel_target . y = _ahrs . get_gyro ( ) . y ;
2014-08-20 10:14:25 -03:00
// accel limit desired yaw rate
2015-11-24 17:11:50 -04:00
if ( get_accel_yaw_max_radss ( ) > 0.0f ) {
float rate_change_limit_rads = get_accel_yaw_max_radss ( ) * _dt ;
2021-04-14 12:42:42 -03:00
float rate_change_rads = yaw_rate_bf_rads - _ang_vel_target . z ;
2015-11-24 17:11:50 -04:00
rate_change_rads = constrain_float ( rate_change_rads , - rate_change_limit_rads , rate_change_limit_rads ) ;
2021-04-14 12:42:42 -03:00
_ang_vel_target . z + = rate_change_rads ;
2014-08-20 10:14:25 -03:00
} else {
2021-04-14 12:42:42 -03:00
_ang_vel_target . z = yaw_rate_bf_rads ;
2014-08-20 10:14:25 -03:00
}
integrate_bf_rate_error_to_angle_errors ( ) ;
2015-11-24 23:28:42 -04:00
_att_error_rot_vec_rad . x = 0 ;
_att_error_rot_vec_rad . y = 0 ;
2014-08-20 10:14:25 -03:00
// update our earth-frame angle targets
2015-12-02 14:45:34 -04:00
Vector3f att_error_euler_rad ;
2015-11-24 20:18:35 -04:00
// convert angle error rotation vector into 321-intrinsic euler angle difference
// NOTE: this results an an approximation linearized about the vehicle's attitude
2019-07-16 03:03:22 -03:00
if ( ang_vel_to_euler_rate ( Vector3f ( _ahrs . roll , _ahrs . pitch , _ahrs . yaw ) , _att_error_rot_vec_rad , att_error_euler_rad ) ) {
2021-04-14 12:42:42 -03:00
_euler_angle_target . x = wrap_PI ( att_error_euler_rad . x + _ahrs . roll ) ;
_euler_angle_target . y = wrap_PI ( att_error_euler_rad . y + _ahrs . pitch ) ;
_euler_angle_target . z = wrap_2PI ( att_error_euler_rad . z + _ahrs . yaw ) ;
2014-08-22 10:50:33 -03:00
}
2014-08-20 10:14:25 -03:00
// handle flipping over pitch axis
2021-04-14 12:42:42 -03:00
if ( _euler_angle_target . y > M_PI / 2.0f ) {
_euler_angle_target . x = wrap_PI ( _euler_angle_target . x + M_PI ) ;
_euler_angle_target . y = wrap_PI ( M_PI - _euler_angle_target . x ) ;
_euler_angle_target . z = wrap_2PI ( _euler_angle_target . z + M_PI ) ;
2014-08-20 10:14:25 -03:00
}
2021-04-14 12:42:42 -03:00
if ( _euler_angle_target . y < - M_PI / 2.0f ) {
_euler_angle_target . x = wrap_PI ( _euler_angle_target . x + M_PI ) ;
_euler_angle_target . y = wrap_PI ( - M_PI - _euler_angle_target . x ) ;
_euler_angle_target . z = wrap_2PI ( _euler_angle_target . z + M_PI ) ;
2014-08-20 10:14:25 -03:00
}
// convert body-frame angle errors to body-frame rate targets
2021-04-14 12:42:42 -03:00
_ang_vel_body = update_ang_vel_target_from_att_error ( _att_error_rot_vec_rad ) ;
2014-08-20 10:14:25 -03:00
// set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
2021-04-14 12:42:42 -03:00
_ang_vel_body . x = _ang_vel_target . x ;
_ang_vel_body . y = _ang_vel_target . y ;
2014-08-20 10:14:25 -03:00
// add desired target to yaw
2021-04-14 12:42:42 -03:00
_ang_vel_body . z + = _ang_vel_target . z ;
2021-09-11 07:28:01 -03:00
_thrust_error_angle = _att_error_rot_vec_rad . xy ( ) . length ( ) ;
2016-06-24 04:20:21 -03:00
}
void AC_AttitudeControl_Heli : : integrate_bf_rate_error_to_angle_errors ( )
{
// Integrate the angular velocity error into the attitude error
2021-04-14 12:42:42 -03:00
_att_error_rot_vec_rad + = ( _ang_vel_target - _ahrs . get_gyro ( ) ) * _dt ;
2016-06-24 04:20:21 -03:00
// Constrain attitude error
_att_error_rot_vec_rad . x = constrain_float ( _att_error_rot_vec_rad . x , - AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD , AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ) ;
_att_error_rot_vec_rad . y = constrain_float ( _att_error_rot_vec_rad . y , - AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD , AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ) ;
_att_error_rot_vec_rad . z = constrain_float ( _att_error_rot_vec_rad . z , - AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD , AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ) ;
2014-08-20 10:14:25 -03:00
}
2015-11-20 15:44:29 -04:00
// subclass non-passthrough too, for external gyro, no flybar
2015-11-28 13:56:25 -04:00
void AC_AttitudeControl_Heli : : input_rate_bf_roll_pitch_yaw ( float roll_rate_bf_cds , float pitch_rate_bf_cds , float yaw_rate_bf_cds )
2015-11-20 15:44:29 -04:00
{
2015-11-28 13:56:25 -04:00
_passthrough_yaw = yaw_rate_bf_cds ;
2015-11-20 15:44:29 -04:00
2015-11-28 13:56:25 -04:00
AC_AttitudeControl : : input_rate_bf_roll_pitch_yaw ( roll_rate_bf_cds , pitch_rate_bf_cds , yaw_rate_bf_cds ) ;
2015-11-20 15:44:29 -04:00
}
2014-01-29 09:50:32 -04:00
//
// rate controller (body-frame) methods
//
// rate_controller_run - run lowest level rate controller and send outputs to the motors
// should be called at 100hz or more
void AC_AttitudeControl_Heli : : rate_controller_run ( )
{
2021-04-14 12:42:42 -03:00
_ang_vel_body + = _sysid_ang_vel_body ;
2019-09-29 23:30:13 -03:00
2017-03-02 07:49:25 -04:00
Vector3f gyro_latest = _ahrs . get_gyro_latest ( ) ;
2014-01-29 09:50:32 -04:00
// call rate controllers and send output to motors object
2014-08-20 10:14:25 -03:00
// if using a flybar passthrough roll and pitch directly to motors
if ( _flags_heli . flybar_passthrough ) {
2019-07-16 03:03:22 -03:00
_motors . set_roll ( _passthrough_roll / 4500.0f ) ;
_motors . set_pitch ( _passthrough_pitch / 4500.0f ) ;
2014-08-20 10:14:25 -03:00
} else {
2021-04-14 12:42:42 -03:00
rate_bf_to_motor_roll_pitch ( gyro_latest , _ang_vel_body . x , _ang_vel_body . y ) ;
2014-07-03 16:49:48 -03:00
}
2015-06-22 02:49:25 -03:00
if ( _flags_heli . tail_passthrough ) {
2019-07-16 03:03:22 -03:00
_motors . set_yaw ( _passthrough_yaw / 4500.0f ) ;
2015-06-22 02:49:25 -03:00
} else {
2021-04-14 12:42:42 -03:00
_motors . set_yaw ( rate_target_to_motor_yaw ( gyro_latest . z , _ang_vel_body . z ) ) ;
2015-06-22 02:49:25 -03:00
}
2019-09-29 23:30:13 -03:00
2021-04-14 12:42:42 -03:00
_sysid_ang_vel_body . zero ( ) ;
2019-09-29 23:30:13 -03:00
_actuator_sysid . zero ( ) ;
2014-01-29 09:50:32 -04:00
}
2016-05-23 12:12:14 -03:00
// Update Alt_Hold angle maximum
void AC_AttitudeControl_Heli : : update_althold_lean_angle_max ( float throttle_in )
{
2020-01-28 21:57:53 -04:00
float althold_lean_angle_max = acosf ( constrain_float ( throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX , 0.0f , 1.0f ) ) ;
2019-07-16 03:03:22 -03:00
_althold_lean_angle_max = _althold_lean_angle_max + ( _dt / ( _dt + _angle_limit_tc ) ) * ( althold_lean_angle_max - _althold_lean_angle_max ) ;
2015-06-23 10:41:47 -03:00
}
2014-01-29 09:50:32 -04:00
//
// private methods
//
//
// body-frame rate controller
//
2015-11-24 17:11:50 -04:00
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
2017-03-02 07:49:25 -04:00
void AC_AttitudeControl_Heli : : rate_bf_to_motor_roll_pitch ( const Vector3f & rate_rads , float rate_roll_target_rads , float rate_pitch_target_rads )
2014-01-29 09:50:32 -04:00
{
2019-07-16 03:03:22 -03:00
if ( _flags_heli . leaky_i ) {
_pid_rate_roll . update_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ;
}
2020-11-17 23:38:18 -04:00
float roll_pid = _pid_rate_roll . update_all ( rate_roll_target_rads , rate_rads . x , _motors . limit . roll ) + _actuator_sysid . x ;
2014-01-29 09:50:32 -04:00
2019-07-16 03:03:22 -03:00
if ( _flags_heli . leaky_i ) {
_pid_rate_pitch . update_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ;
2014-01-29 09:50:32 -04:00
}
2019-07-16 03:03:22 -03:00
2020-11-17 23:38:18 -04:00
float pitch_pid = _pid_rate_pitch . update_all ( rate_pitch_target_rads , rate_rads . y , _motors . limit . pitch ) + _actuator_sysid . y ;
2019-07-16 03:03:22 -03:00
// use pid library to calculate ff
float roll_ff = _pid_rate_roll . get_ff ( ) ;
float pitch_ff = _pid_rate_pitch . get_ff ( ) ;
2014-01-29 09:50:32 -04:00
// add feed forward and final output
2019-07-16 03:03:22 -03:00
float roll_out = roll_pid + roll_ff ;
float pitch_out = pitch_pid + pitch_ff ;
2014-01-29 09:50:32 -04:00
// constrain output and update limit flags
2015-05-08 15:41:27 -03:00
if ( fabsf ( roll_out ) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) {
2019-07-16 03:03:22 -03:00
roll_out = constrain_float ( roll_out , - AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) ;
2014-01-29 09:50:32 -04:00
_flags_heli . limit_roll = true ;
2019-07-16 03:03:22 -03:00
} else {
2014-01-29 09:50:32 -04:00
_flags_heli . limit_roll = false ;
}
2015-05-08 15:41:27 -03:00
if ( fabsf ( pitch_out ) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) {
2019-07-16 03:03:22 -03:00
pitch_out = constrain_float ( pitch_out , - AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) ;
2014-01-29 09:50:32 -04:00
_flags_heli . limit_pitch = true ;
2019-07-16 03:03:22 -03:00
} else {
2014-01-29 09:50:32 -04:00
_flags_heli . limit_pitch = false ;
}
// output to motors
2014-02-10 00:24:11 -04:00
_motors . set_roll ( roll_out ) ;
_motors . set_pitch ( pitch_out ) ;
2014-01-29 09:50:32 -04:00
2015-09-21 23:35:53 -03:00
// Piro-Comp, or Pirouette Compensation is a pre-compensation calculation, which basically rotates the Roll and Pitch Rate I-terms as the
// helicopter rotates in yaw. Much of the built-up I-term is needed to tip the disk into the incoming wind. Fast yawing can create an instability
// as the built-up I-term in one axis must be reduced, while the other increases. This helps solve that by rotating the I-terms before the error occurs.
// It does assume that the rotor aerodynamics and mechanics are essentially symmetrical about the main shaft, which is a generally valid assumption.
2019-07-16 03:03:22 -03:00
if ( _piro_comp_enabled ) {
2014-01-29 09:50:32 -04:00
2019-04-04 01:51:19 -03:00
// used to hold current I-terms while doing piro comp:
2019-07-16 03:03:22 -03:00
const float piro_roll_i = _pid_rate_roll . get_i ( ) ;
const float piro_pitch_i = _pid_rate_pitch . get_i ( ) ;
2014-01-29 09:50:32 -04:00
Vector2f yawratevector ;
2017-03-02 07:49:25 -04:00
yawratevector . x = cosf ( - rate_rads . z * _dt ) ;
yawratevector . y = sinf ( - rate_rads . z * _dt ) ;
2014-01-29 09:50:32 -04:00
yawratevector . normalize ( ) ;
2019-07-16 03:03:22 -03:00
_pid_rate_roll . set_integrator ( piro_roll_i * yawratevector . x - piro_pitch_i * yawratevector . y ) ;
_pid_rate_pitch . set_integrator ( piro_pitch_i * yawratevector . x + piro_roll_i * yawratevector . y ) ;
2014-01-29 09:50:32 -04:00
}
2015-09-21 23:35:53 -03:00
2014-01-29 09:50:32 -04:00
}
2015-11-24 17:11:50 -04:00
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second
2017-03-02 07:49:25 -04:00
float AC_AttitudeControl_Heli : : rate_target_to_motor_yaw ( float rate_yaw_actual_rads , float rate_target_rads )
2014-01-29 09:50:32 -04:00
{
2019-07-16 03:03:22 -03:00
if ( ! ( ( AP_MotorsHeli & ) _motors ) . rotor_runup_complete ( ) ) {
_pid_rate_yaw . update_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ;
2014-01-29 09:50:32 -04:00
}
2019-07-16 03:03:22 -03:00
2020-11-17 23:38:18 -04:00
float pid = _pid_rate_yaw . update_all ( rate_target_rads , rate_yaw_actual_rads , _motors . limit . yaw ) + _actuator_sysid . z ;
2019-07-16 03:03:22 -03:00
// use pid library to calculate ff
2019-10-28 07:48:53 -03:00
float vff = _pid_rate_yaw . get_ff ( ) * _feedforward_scalar ;
2019-07-16 03:03:22 -03:00
2014-01-30 03:19:59 -04:00
// add feed forward
2019-07-16 03:03:22 -03:00
float yaw_out = pid + vff ;
2014-01-29 09:50:32 -04:00
2014-01-30 03:19:59 -04:00
// constrain output and update limit flag
2015-05-08 15:41:27 -03:00
if ( fabsf ( yaw_out ) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX ) {
2019-07-16 03:03:22 -03:00
yaw_out = constrain_float ( yaw_out , - AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX ) ;
2014-01-30 03:19:59 -04:00
_flags_heli . limit_yaw = true ;
2019-07-16 03:03:22 -03:00
} else {
2014-01-30 03:19:59 -04:00
_flags_heli . limit_yaw = false ;
}
2014-01-29 09:50:32 -04:00
2014-01-30 03:19:59 -04:00
// output to motors
return yaw_out ;
2014-01-29 09:50:32 -04:00
}
//
// throttle functions
//
2016-03-21 07:57:39 -03:00
void AC_AttitudeControl_Heli : : set_throttle_out ( float throttle_in , bool apply_angle_boost , float filter_cutoff )
2014-01-29 09:50:32 -04:00
{
2016-03-21 07:57:39 -03:00
_throttle_in = throttle_in ;
2016-06-21 09:04:53 -03:00
update_althold_lean_angle_max ( throttle_in ) ;
2016-03-21 07:57:39 -03:00
_motors . set_throttle_filter_cutoff ( filter_cutoff ) ;
_motors . set_throttle ( throttle_in ) ;
// Clear angle_boost for logging purposes
2016-01-03 23:46:25 -04:00
_angle_boost = 0.0f ;
2014-01-29 09:50:32 -04:00
}
2017-08-27 20:48:36 -03:00
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
void AC_AttitudeControl_Heli : : input_euler_angle_roll_pitch_euler_rate_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_rate_cds )
2017-08-27 20:48:36 -03:00
{
if ( _inverted_flight ) {
euler_roll_angle_cd = wrap_180_cd ( euler_roll_angle_cd + 18000 ) ;
}
2017-06-25 11:33:16 -03:00
AC_AttitudeControl : : input_euler_angle_roll_pitch_euler_rate_yaw ( euler_roll_angle_cd , euler_pitch_angle_cd , euler_yaw_rate_cds ) ;
2017-08-27 20:48:36 -03:00
}
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
void AC_AttitudeControl_Heli : : input_euler_angle_roll_pitch_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_angle_cd , bool slew_yaw )
2017-08-27 20:48:36 -03:00
{
if ( _inverted_flight ) {
euler_roll_angle_cd = wrap_180_cd ( euler_roll_angle_cd + 18000 ) ;
}
2017-06-25 11:33:16 -03:00
AC_AttitudeControl : : input_euler_angle_roll_pitch_yaw ( euler_roll_angle_cd , euler_pitch_angle_cd , euler_yaw_angle_cd , slew_yaw ) ;
2017-08-27 20:48:36 -03:00
}