APM:Libraries
AP_AutoTune.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_Param/AP_Param.h>
5 #include <DataFlash/DataFlash.h>
6 
7 class AP_AutoTune {
8 public:
9  struct ATGains {
10  AP_Float tau;
11  AP_Float P;
12  AP_Float I;
13  AP_Float D;
14  AP_Float FF;
15  AP_Int16 rmax;
16  AP_Int16 imax;
17  };
18 
19  enum ATType {
22  };
23 
24  struct PACKED log_ATRP {
26  uint64_t time_us;
27  uint8_t type;
28  uint8_t state;
29  int16_t servo;
30  float demanded;
31  float achieved;
32  float P;
33  };
34 
35 
36  // constructor
37  AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash);
38 
39  // called when autotune mode is entered
40  void start(void);
41 
42  // called to stop autotune and restore gains when user leaves
43  // autotune
44  void stop(void);
45 
46  // update called whenever autotune mode is active. This is
47  // typically at 50Hz
48  void update(float desired_rate, float achieved_rate, float servo_out);
49 
50  // are we running?
51  bool running:1;
52 
53 private:
54  // the current gains
56 
57  // what type of autotune is this
59 
61 
63 
64  // did we saturate surfaces?
66 
67  // values to restore if we leave autotune mode
69 
70  // values we last saved
72 
73  // values to save on the next save event
75 
76  // time when we last saved
77  uint32_t last_save_ms = 0;
78 
79  // the demanded/achieved state
85 
86  // when we entered the current state
87  uint32_t state_enter_ms = 0;
88 
89  void check_save(void);
90  void check_state_exit(uint32_t state_time_ms);
91  void save_gains(const ATGains &v);
92 
93  void write_log(float servo, float demanded, float achieved);
94 
95  void log_param_change(float v, const char *suffix);
96  void save_float_if_changed(AP_Float &v, float value, const char *suffix);
97  void save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix);
98 };
void check_save(void)
const AP_Vehicle::FixedWing & aparm
Definition: AP_AutoTune.h:60
ATType type
Definition: AP_AutoTune.h:58
AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, DataFlash_Class &_dataflash)
Definition: AP_AutoTune.cpp:69
void update(float desired_rate, float achieved_rate, float servo_out)
void save_float_if_changed(AP_Float &v, float value, const char *suffix)
ATGains restore
Definition: AP_AutoTune.h:68
bool running
Definition: AP_AutoTune.h:51
void stop(void)
A system for managing and storing variables that are of general interest to the system.
ATGains last_save
Definition: AP_AutoTune.h:71
uint32_t state_enter_ms
Definition: AP_AutoTune.h:87
void save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix)
enum AP_AutoTune::ATState state
float v
Definition: Printf.cpp:15
ATGains & current
Definition: AP_AutoTune.h:55
void check_state_exit(uint32_t state_time_ms)
ATGains next_save
Definition: AP_AutoTune.h:74
void write_log(float servo, float demanded, float achieved)
void log_param_change(float v, const char *suffix)
DataFlash_Class & dataflash
Definition: AP_AutoTune.h:62
uint32_t last_save_ms
Definition: AP_AutoTune.h:77
#define PACKED
Definition: AP_Common.h:28
bool saturated_surfaces
Definition: AP_AutoTune.h:65
void save_gains(const ATGains &v)
float value
void start(void)