123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369 |
- #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
- // @Range: 0.0 0.30
- // @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
- // @Range: 0.0 0.5
- // @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
- // @Units: %
- // @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
- // @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
- // @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
- // @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
- // @Range: 0.0 0.30
- // @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
- // @Range: 0.0 0.5
- // @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
- // @Units: %
- // @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
- // @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
- // @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
- // @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
- // @Range: 0.0 0.50
- // @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
- // @Range: 0.0 0.05
- // @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
- // @Units: %
- // @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
- // @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
- // @User: Standard
- // @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
- // @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),
- // @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
- 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),
- _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)
- {
- 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;
- }
- float althold_lean_angle_max = acosf(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
- _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);
- _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();
- Vector3f gyro_latest = _ahrs.get_gyro_latest();
- _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));
- _motors.set_yaw(get_rate_yaw_pid().update_all(_rate_target_ang_vel.z, gyro_latest.z, _motors.limit.yaw));
- static int f = 0;
- f++;
- if(f>200)
- {
-
- //gcs().send_text(MAV_SEVERITY_INFO, " get_P_pid %d, %d, %d,",(int)((get_rate_roll_pid().get_p()+get_rate_roll_pid().get_i())*1000),(int)((get_rate_pitch_pid().get_p()+get_rate_pitch_pid().get_i())*1000),(int)((get_rate_yaw_pid().get_p()+get_rate_yaw_pid().get_i())*1000));
- //gcs().send_text(MAV_SEVERITY_INFO, " get_I_pid %d, %d, %d,",(int)(get_rate_roll_pid().get_i()*1000),(int)(get_rate_pitch_pid().get_i()*1000),(int)(get_rate_yaw_pid().get_i()*1000));
-
- f=0;
- }
- 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);
- }
- }
|