Skip to content

Commit 52ebc48

Browse files
committed
AC_AttitudeControl: add support to set ILMI param defaults
AC_AttitudeControl: resolving rebase issues AC_AttitudeControl: resolving rebase issues AC_AttitudeControl: Implement default setting of ILMI param for heli AC_AttitudeControl: nested if statement so common default gains between trad heli and copter are not duplicated
1 parent d643e8f commit 52ebc48

2 files changed

Lines changed: 19 additions & 8 deletions

File tree

libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#define AC_ATC_HELI_RATE_RP_IMAX 0.4f
1616
#define AC_ATC_HELI_RATE_RP_FF 0.15f
1717
#define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
18+
#define AC_ATC_HELI_RATE_RP_ILMI 0.05f // Default I-term Leak Minimum
1819
#define AC_ATC_HELI_RATE_YAW_P 0.18f
1920
#define AC_ATC_HELI_RATE_YAW_I 0.12f
2021
#define AC_ATC_HELI_RATE_YAW_D 0.003f
@@ -173,8 +174,8 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl {
173174
.srtau = 1.0
174175
}
175176
};
176-
AC_HELI_PID _pid_rate_roll { rp_defaults };
177-
AC_HELI_PID _pid_rate_pitch { rp_defaults };
177+
AC_HELI_PID _pid_rate_roll { rp_defaults, AC_ATC_HELI_RATE_RP_ILMI };
178+
AC_HELI_PID _pid_rate_pitch { rp_defaults, AC_ATC_HELI_RATE_RP_ILMI };
178179

179180
AC_HELI_PID _pid_rate_yaw {
180181
AC_PID::Defaults{
@@ -189,6 +190,7 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl {
189190
.srmax = 0,
190191
.srtau = 1.0
191192
}
193+
, 0.0f // default_ilmi
192194
};
193195

194196
};

libraries/AC_AttitudeControl/AC_PosControl.cpp

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -49,25 +49,34 @@ extern const AP_HAL::HAL& hal;
4949
# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter
5050
# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
5151
#else
52-
// default gains for Copter / TradHeli
52+
// default gains common between TradHeli and Copter
5353
# define POSCONTROL_D_POS_P 1.0f // vertical position controller P gain default
5454
# define POSCONTROL_D_VEL_P 5.0f // vertical velocity controller P gain default
5555
# define POSCONTROL_D_VEL_IMAX 10.0f // vertical velocity controller IMAX gain default
5656
# define POSCONTROL_D_VEL_FILT_HZ 5.0f // vertical velocity controller input filter
57-
# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D
58-
# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default
57+
# define POSCONTROL_D_VEL_FILT_D_HZ 5.0f // vertical velocity controller input filter for D
5958
# define POSCONTROL_D_ACC_I 0.1f // vertical acceleration controller I gain default
6059
# define POSCONTROL_D_ACC_D 0.0f // vertical acceleration controller D gain default
6160
# define POSCONTROL_D_ACC_IMAX 0.8f // vertical acceleration controller IMAX gain default
6261
# define POSCONTROL_D_ACC_FILT_HZ 20.0f // vertical acceleration controller input filter default
6362
# define POSCONTROL_D_ACC_DT 0.0025f // vertical acceleration controller dt default
6463
# define POSCONTROL_NE_POS_P 1.0f // horizontal position controller P gain default
65-
# define POSCONTROL_NE_VEL_P 2.0f // horizontal velocity controller P gain default
66-
# define POSCONTROL_NE_VEL_I 1.0f // horizontal velocity controller I gain default
67-
# define POSCONTROL_NE_VEL_D 0.25f // horizontal velocity controller D gain default
6864
# define POSCONTROL_NE_VEL_IMAX 10.0f // horizontal velocity controller IMAX gain default
6965
# define POSCONTROL_NE_VEL_FILT_HZ 5.0f // horizontal velocity controller input filter
7066
# define POSCONTROL_NE_VEL_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
67+
#if APM_BUILD_TYPE(APM_BUILD_Heli)
68+
// default gains specific to TradHeli
69+
# define POSCONTROL_D_ACC_P 0.028f // vertical acceleration controller P gain default
70+
# define POSCONTROL_NE_VEL_P 1.0f // horizontal velocity controller P gain default
71+
# define POSCONTROL_NE_VEL_I 0.5f // horizontal velocity controller I gain default
72+
# define POSCONTROL_NE_VEL_D 0.0f // horizontal velocity controller D gain default
73+
#else
74+
// default gains specific to Copter
75+
# define POSCONTROL_D_ACC_P 0.05f // vertical acceleration controller P gain default
76+
# define POSCONTROL_NE_VEL_P 2.0f // horizontal velocity controller P gain default
77+
# define POSCONTROL_NE_VEL_I 1.0f // horizontal velocity controller I gain default
78+
# define POSCONTROL_NE_VEL_D 0.25f // horizontal velocity controller D gain default
79+
#endif
7180
#endif
7281

7382
// vibration compensation gains

0 commit comments

Comments
 (0)