mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_AttitudeControl: tidy AC_PID construction
This commit is contained in:
parent
f8f28ee767
commit
70109f968c
@ -1,6 +1,7 @@
|
|||||||
#include "AC_AttitudeControl_Multi.h"
|
#include "AC_AttitudeControl_Multi.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AC_PID/AC_PID.h>
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
|
const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
|
||||||
@ -244,10 +245,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
|
|||||||
|
|
||||||
AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) :
|
AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) :
|
||||||
AC_AttitudeControl(ahrs, aparm, motors),
|
AC_AttitudeControl(ahrs, aparm, motors),
|
||||||
_motors_multi(motors),
|
_motors_multi(motors)
|
||||||
_pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ),
|
|
||||||
_pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ),
|
|
||||||
_pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, AC_ATC_MULTI_RATE_YAW_FILT_HZ, 0.0f)
|
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
|
@ -93,9 +93,49 @@ protected:
|
|||||||
float get_throttle_avg_max(float throttle_in);
|
float get_throttle_avg_max(float throttle_in);
|
||||||
|
|
||||||
AP_MotorsMulticopter& _motors_multi;
|
AP_MotorsMulticopter& _motors_multi;
|
||||||
AC_PID _pid_rate_roll;
|
AC_PID _pid_rate_roll {
|
||||||
AC_PID _pid_rate_pitch;
|
AC_PID::Defaults{
|
||||||
AC_PID _pid_rate_yaw;
|
.p = AC_ATC_MULTI_RATE_RP_P,
|
||||||
|
.i = AC_ATC_MULTI_RATE_RP_I,
|
||||||
|
.d = AC_ATC_MULTI_RATE_RP_D,
|
||||||
|
.ff = 0.0f,
|
||||||
|
.imax = AC_ATC_MULTI_RATE_RP_IMAX,
|
||||||
|
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
|
||||||
|
.filt_E_hz = 0.0f,
|
||||||
|
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
|
||||||
|
.srmax = 0,
|
||||||
|
.srtau = 1.0
|
||||||
|
}
|
||||||
|
};
|
||||||
|
AC_PID _pid_rate_pitch{
|
||||||
|
AC_PID::Defaults{
|
||||||
|
.p = AC_ATC_MULTI_RATE_RP_P,
|
||||||
|
.i = AC_ATC_MULTI_RATE_RP_I,
|
||||||
|
.d = AC_ATC_MULTI_RATE_RP_D,
|
||||||
|
.ff = 0.0f,
|
||||||
|
.imax = AC_ATC_MULTI_RATE_RP_IMAX,
|
||||||
|
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
|
||||||
|
.filt_E_hz = 0.0f,
|
||||||
|
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
|
||||||
|
.srmax = 0,
|
||||||
|
.srtau = 1.0
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
AC_PID _pid_rate_yaw{
|
||||||
|
AC_PID::Defaults{
|
||||||
|
.p = AC_ATC_MULTI_RATE_YAW_P,
|
||||||
|
.i = AC_ATC_MULTI_RATE_YAW_I,
|
||||||
|
.d = AC_ATC_MULTI_RATE_YAW_D,
|
||||||
|
.ff = 0.0f,
|
||||||
|
.imax = AC_ATC_MULTI_RATE_YAW_IMAX,
|
||||||
|
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
|
||||||
|
.filt_E_hz = AC_ATC_MULTI_RATE_YAW_FILT_HZ,
|
||||||
|
.filt_D_hz = 0.0f,
|
||||||
|
.srmax = 0,
|
||||||
|
.srtau = 1.0
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
|
AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
|
||||||
AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
|
AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
|
||||||
|
Loading…
Reference in New Issue
Block a user