APM:Libraries
AP_Tuning.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <DataFlash/DataFlash.h>
6 
7 /*
8  transmitter tuning library. Meant to be subclassed per vehicle type
9  */
10 class AP_Tuning
11 {
12 public:
13  struct tuning_set {
14  uint8_t set;
15  uint8_t num_parms;
16  const uint8_t *parms;
17  };
18 
19  struct tuning_name {
20  uint8_t parm;
21  const char *name;
22  };
23 
24  // constructor
25  AP_Tuning(const struct tuning_set *sets, const struct tuning_name *names) :
26  tuning_sets(sets),
27  tuning_names(names) {
29  }
30 
31  // var_info for holding Parameter information
32  static const struct AP_Param::GroupInfo var_info[];
33 
34  // update function called on new radio frames
35  void check_input(uint8_t flightmode);
36 
37  // base parameter number for tuning sets of parameters in one flight
38  const uint8_t set_base = 100;
39 
40 private:
41  AP_Int8 channel;
42  AP_Int16 channel_min;
43  AP_Int16 channel_max;
44  AP_Int8 selector;
45  AP_Float range;
46  AP_Int8 mode_revert;
47  AP_Float error_threshold;
48 
49  // when selector was triggered
51 
52  // are we waiting for channel mid-point?
54 
55  // last input from tuning channel
57 
58  // mid-value for current parameter
59  float center_value;
60 
61  uint32_t last_check_ms;
62 
64 
65  // the parameter we are tuning
66  uint8_t current_parm;
67 
68  // current index into the parameter set
70 
71  // current parameter set
72  uint8_t current_set;
73 
74  // true if tune has changed
75  bool changed:1;
76 
77  // mask of params in set that need reverting
78  uint32_t need_revert;
79 
80  // last flight mode we were tuning in
81  uint8_t last_flightmode;
82 
83  // last time we reported controller error
85 
88 
89  void check_selector_switch(void);
90  void re_center(void);
91  void next_parameter(void);
92  void save_parameters(void);
93  void revert_parameters(void);
94  const char *get_tuning_name(uint8_t parm);
95  void check_controller_error(void);
96 
97 protected:
98  // virtual functions that must be implemented in vehicle subclass
99  virtual AP_Float *get_param_pointer(uint8_t parm) = 0;
100  virtual void save_value(uint8_t parm) = 0;
101  virtual void reload_value(uint8_t parm) = 0;
102  virtual void set_value(uint8_t parm, float value) = 0;
103  virtual float controller_error(uint8_t parm) = 0;
104 
105  // parmset is in vehicle subclass var table
106  AP_Int16 parmset;
107 };
uint8_t current_set
Definition: AP_Tuning.h:72
uint32_t last_check_ms
Definition: AP_Tuning.h:61
uint32_t selector_start_ms
Definition: AP_Tuning.h:50
virtual float controller_error(uint8_t parm)=0
AP_Tuning(const struct tuning_set *sets, const struct tuning_name *names)
Definition: AP_Tuning.h:25
void check_selector_switch(void)
Definition: AP_Tuning.cpp:62
void save_parameters(void)
Definition: AP_Tuning.cpp:240
const char * get_tuning_name(uint8_t parm)
Definition: AP_Tuning.cpp:315
uint8_t current_parm
Definition: AP_Tuning.h:66
void Log_Write_Parameter_Tuning(float value)
Definition: AP_Tuning.cpp:227
AP_Int16 channel_max
Definition: AP_Tuning.h:43
uint32_t last_controller_error_ms
Definition: AP_Tuning.h:84
const uint8_t set_base
Definition: AP_Tuning.h:38
bool mid_point_wait
Definition: AP_Tuning.h:53
virtual void save_value(uint8_t parm)=0
AP_Int16 parmset
Definition: AP_Tuning.h:106
float last_channel_value
Definition: AP_Tuning.h:56
virtual AP_Float * get_param_pointer(uint8_t parm)=0
uint8_t current_parm_index
Definition: AP_Tuning.h:69
void revert_parameters(void)
Definition: AP_Tuning.cpp:263
AP_Int8 mode_revert
Definition: AP_Tuning.h:46
AP_Float range
Definition: AP_Tuning.h:45
void check_controller_error(void)
Definition: AP_Tuning.cpp:328
const char * name
Definition: AP_Tuning.h:21
virtual void reload_value(uint8_t parm)=0
float center_value
Definition: AP_Tuning.h:59
const uint8_t * parms
Definition: AP_Tuning.h:16
AP_Float error_threshold
Definition: AP_Tuning.h:47
AP_Int8 channel
Definition: AP_Tuning.h:41
virtual void set_value(uint8_t parm, float value)=0
Common definitions and utility routines for the ArduPilot libraries.
const tuning_set * tuning_sets
Definition: AP_Tuning.h:86
void check_input(uint8_t flightmode)
Definition: AP_Tuning.cpp:120
void re_center(void)
Definition: AP_Tuning.cpp:108
float value
bool changed
Definition: AP_Tuning.h:75
AP_Int16 channel_min
Definition: AP_Tuning.h:42
uint8_t last_flightmode
Definition: AP_Tuning.h:81
uint32_t need_revert
Definition: AP_Tuning.h:78
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Tuning.h:32
const tuning_name * tuning_names
Definition: AP_Tuning.h:87
AP_Int8 selector
Definition: AP_Tuning.h:44
void next_parameter(void)
Definition: AP_Tuning.cpp:287
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214