Path: blob/master/libraries/APM_Control/AP_AutoTune.h
9546 views
#pragma once12#include <AP_Logger/LogStructure.h>3#include <AP_Param/AP_Param.h>4#include <AP_Vehicle/AP_FixedWing.h>5#include <Filter/SlewLimiter.h>67#include <Filter/ModeFilter.h>89class AP_AutoTune10{11public:12struct ATGains {13AP_Float tau;14AP_Int16 rmax_pos;15AP_Int16 rmax_neg;16float FF, P, I, D, IMAX;17float flt_T, flt_E, flt_D;18};1920enum ATType {21AUTOTUNE_ROLL = 0,22AUTOTUNE_PITCH = 1,23AUTOTUNE_YAW = 2,24};2526enum Options {27DISABLE_FLTD_UPDATE = 0,28DISABLE_FLTT_UPDATE = 129};3031struct PACKED log_ATRP {32LOG_PACKET_HEADER;33uint64_t time_us;34uint8_t type;35uint8_t state;36float actuator;37float P_slew;38float D_slew;39float FF_single;40float FF;41float P;42float I;43float D;44uint8_t action;45float rmax;46float tau;47};4849// constructor50AP_AutoTune(ATGains &_gains, ATType type, const AP_FixedWing &parms, class AC_PID &rpid);5152// called when autotune mode is entered53void start(void);5455// called to stop autotune and restore gains when user leaves56// autotune57void stop(void);5859// update called whenever autotune mode is active. This is60// called at the main loop rate61void update(struct AP_PIDInfo &pid_info, float scaler, float angle_err_deg);6263// are we running?64bool running;6566static const char *axis_string(ATType _type);6768private:69// the current gains70ATGains ¤t;71class AC_PID &rpid;7273// what type of autotune is this74ATType type;7576const AP_FixedWing &aparm;7778// values to restore if we leave autotune mode79ATGains restore;80ATGains last_save;8182// last logging time83uint32_t last_log_ms;8485// the demanded/achieved state86enum class ATState {IDLE,87DEMAND_POS,88DEMAND_NEG89};90ATState state;9192// the demanded/achieved state93enum class Action {NONE,94LOW_RATE,95SHORT,96RAISE_PD,97LOWER_PD,98IDLE_LOWER_PD,99RAISE_D,100RAISE_P,101LOWER_D,102LOWER_P103};104Action action;105106// when we entered the current state107uint32_t state_enter_ms;108109void check_state_exit(uint32_t state_time_ms);110void save_gains(void);111112void save_float_if_changed(AP_Float &v, float value);113void save_int16_if_changed(AP_Int16 &v, int16_t value);114void state_change(ATState newstate);115const char *axis_string(void) const;116117// get gains with PID components118ATGains get_gains(void);119void restore_gains(void);120121// update rmax and tau towards target122void update_rmax();123124bool has_option(Options option) {125return (aparm.autotune_options.get() & uint32_t(1<<uint32_t(option))) != 0;126}127128// 5 point mode filter for FF estimate129ModeFilterFloat_Size5 ff_filter;130131LowPassFilterConstDtFloat actuator_filter;132LowPassFilterConstDtFloat rate_filter;133LowPassFilterConstDtFloat target_filter;134135// separate slew limiters for P and D136float slew_limit_max, slew_limit_tau;137SlewLimiter slew_limiter_P{slew_limit_max, slew_limit_tau};138SlewLimiter slew_limiter_D{slew_limit_max, slew_limit_tau};139140float max_actuator;141float min_actuator;142float max_rate;143float min_rate;144float max_target;145float min_target;146float max_P;147float max_D;148float min_Dmod;149float max_Dmod;150float max_SRate_P;151float max_SRate_D;152float FF_single;153uint16_t ff_count;154float dt;155float D_limit;156float P_limit;157uint32_t D_set_ms;158uint32_t P_set_ms;159uint8_t done_count;160};161162163