mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_AttControl: remove rate PIDs
This commit is contained in:
parent
17c9db08f3
commit
75042e5e27
@ -13,38 +13,6 @@
|
||||
#include <AC_PID/AC_PID.h>
|
||||
#include <AC_PID/AC_P.h>
|
||||
|
||||
// default rate controller PID gains
|
||||
#ifndef AC_ATC_MULTI_RATE_RP_P
|
||||
# define AC_ATC_MULTI_RATE_RP_P 0.150f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_RP_I
|
||||
# define AC_ATC_MULTI_RATE_RP_I 0.100f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_RP_D
|
||||
# define AC_ATC_MULTI_RATE_RP_D 0.004f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_RP_IMAX
|
||||
# define AC_ATC_MULTI_RATE_RP_IMAX 2000.0f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
|
||||
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_YAW_P
|
||||
# define AC_ATC_MULTI_RATE_YAW_P 0.200f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_YAW_I
|
||||
# define AC_ATC_MULTI_RATE_YAW_I 0.020f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_YAW_D
|
||||
# define AC_ATC_MULTI_RATE_YAW_D 0.0f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_YAW_IMAX
|
||||
# define AC_ATC_MULTI_RATE_YAW_IMAX 1000.0f
|
||||
#endif
|
||||
#ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
|
||||
# define AC_ATC_MULTI_RATE_YAW_FILT_HZ 5.0f
|
||||
#endif
|
||||
|
||||
// TODO: change the name or move to AP_Math? eliminate in favor of degrees(100)?
|
||||
#define AC_ATTITUDE_CONTROL_DEGX100 5729.57795f // constant to convert from radians to centidegrees
|
||||
|
||||
@ -89,10 +57,7 @@ public:
|
||||
_throttle_in_filt(AC_ATTITUDE_CONTROL_ALTHOLD_LEANANGLE_FILT_HZ),
|
||||
_ahrs(ahrs),
|
||||
_aparm(aparm),
|
||||
_motors(motors),
|
||||
_pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
|
||||
_pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
|
||||
_pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_YAW_FILT_HZ, dt)
|
||||
_motors(motors)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
@ -342,9 +307,6 @@ protected:
|
||||
AC_P _p_angle_roll;
|
||||
AC_P _p_angle_pitch;
|
||||
AC_P _p_angle_yaw;
|
||||
AC_PID _pid_rate_roll;
|
||||
AC_PID _pid_rate_pitch;
|
||||
AC_PID _pid_rate_yaw;
|
||||
|
||||
// Intersampling period in seconds
|
||||
float _dt;
|
||||
|
Loading…
Reference in New Issue
Block a user