Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/APM_Control/AP_AutoTune.h
Views: 1798
#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;6566private:67// the current gains68ATGains ¤t;69class AC_PID &rpid;7071// what type of autotune is this72ATType type;7374const AP_FixedWing &aparm;7576// values to restore if we leave autotune mode77ATGains restore;78ATGains last_save;7980// last logging time81uint32_t last_log_ms;8283// the demanded/achieved state84enum class ATState {IDLE,85DEMAND_POS,86DEMAND_NEG87};88ATState state;8990// the demanded/achieved state91enum class Action {NONE,92LOW_RATE,93SHORT,94RAISE_PD,95LOWER_PD,96IDLE_LOWER_PD,97RAISE_D,98RAISE_P,99LOWER_D,100LOWER_P101};102Action action;103104// when we entered the current state105uint32_t state_enter_ms;106107void check_state_exit(uint32_t state_time_ms);108void save_gains(void);109110void save_float_if_changed(AP_Float &v, float value);111void save_int16_if_changed(AP_Int16 &v, int16_t value);112void state_change(ATState newstate);113const char *axis_string(void) const;114115// get gains with PID components116ATGains get_gains(void);117void restore_gains(void);118119// update rmax and tau towards target120void update_rmax();121122bool has_option(Options option) {123return (aparm.autotune_options.get() & uint32_t(1<<uint32_t(option))) != 0;124}125126// 5 point mode filter for FF estimate127ModeFilterFloat_Size5 ff_filter;128129LowPassFilterConstDtFloat actuator_filter;130LowPassFilterConstDtFloat rate_filter;131LowPassFilterConstDtFloat target_filter;132133// separate slew limiters for P and D134float slew_limit_max, slew_limit_tau;135SlewLimiter slew_limiter_P{slew_limit_max, slew_limit_tau};136SlewLimiter slew_limiter_D{slew_limit_max, slew_limit_tau};137138float max_actuator;139float min_actuator;140float max_rate;141float min_rate;142float max_target;143float min_target;144float max_P;145float max_D;146float min_Dmod;147float max_Dmod;148float max_SRate_P;149float max_SRate_D;150float FF_single;151uint16_t ff_count;152float dt;153float D_limit;154float P_limit;155uint32_t D_set_ms;156uint32_t P_set_ms;157uint8_t done_count;158};159160161