APM:Libraries
AP_Tuning.cpp
Go to the documentation of this file.
1 #include "AP_Tuning.h"
2 #include <GCS_MAVLink/GCS.h>
4 
5 extern const AP_HAL::HAL& hal;
6 
8  // @Param: CHAN
9  // @DisplayName: Transmitter tuning channel
10  // @Description: This sets the channel for transmitter tuning. This should be connected to a knob or slider on your transmitter. It needs to be setup to use the PWM range given by TUNE_CHAN_MIN to TUNE_CHAN_MAX
11  // @Values: 0:Disable,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
12  // @User: Standard
13  AP_GROUPINFO("CHAN", 1, AP_Tuning, channel, 0),
14 
15  // @Param: CHAN_MIN
16  // @DisplayName: Transmitter tuning channel minimum pwm
17  // @Description: This sets the PWM lower limit for the tuning channel
18  // @Range: 900 2100
19  // @User: Standard
20  AP_GROUPINFO("CHAN_MIN", 2, AP_Tuning, channel_min, 1000),
21 
22  // @Param: CHAN_MAX
23  // @DisplayName: Transmitter tuning channel maximum pwm
24  // @Description: This sets the PWM upper limit for the tuning channel
25  // @Range: 900 2100
26  // @User: Standard
27  AP_GROUPINFO("CHAN_MAX", 3, AP_Tuning, channel_max, 2000),
28 
29  // @Param: SELECTOR
30  // @DisplayName: Transmitter tuning selector channel
31  // @Description: This sets the channel for the transmitter tuning selector switch. This should be a 2 position switch, preferably spring loaded. A PWM above 1700 means high, below 1300 means low. If no selector is set then you won't be able to switch between parameters during flight or re-center the tuning knob
32  // @Values: 0:Disable,1:Chan1,2:Chan3,3:Chan3,4:Chan4,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
33  // @User: Standard
34  AP_GROUPINFO("SELECTOR", 4, AP_Tuning, selector, 0),
35 
36  // @Param: RANGE
37  // @DisplayName: Transmitter tuning range
38  // @Description: This sets the range over which tuning will change a parameter. A value of 2 means the tuning parameter will go from 0.5 times the start value to 2x the start value over the range of the tuning channel
39  // @User: Standard
40  AP_GROUPINFO("RANGE", 5, AP_Tuning, range, 2.0f),
41 
42  // @Param: MODE_REVERT
43  // @DisplayName: Revert on mode change
44  // @Description: This controls whether tuning values will revert on a flight mode change.
45  // @Values: 0:Disable,1:Enable
46  // @User: Standard
47  AP_GROUPINFO("MODE_REVERT", 6, AP_Tuning, mode_revert, 1),
48 
49  // @Param: ERR_THRESH
50  // @DisplayName: Controller error threshold
51  // @Description: This sets the controller error threshold above which an alarm will sound and a message will be sent to the GCS to warn of controller instability
52  // @Range: 0 1
53  // @User: Standard
54  AP_GROUPINFO("ERR_THRESH", 7, AP_Tuning, error_threshold, 0.15f),
55 
57 };
58 
59 /*
60  handle selector switch input
61 */
63 {
64  if (selector == 0) {
65  // no selector switch enabled
66  return;
67  }
69  if (selchan == nullptr) {
70  return;
71  }
72  uint16_t selector_in = selchan->get_radio_in();
73  if (selector_in >= 1700) {
74  // high selector
75  if (selector_start_ms == 0) {
77  }
78  uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
79  if (hold_time > 5000 && changed) {
80  // save tune
82  re_center();
83  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: Saved");
85  changed = false;
86  need_revert = 0;
87  }
88  } else if (selector_in <= 1300) {
89  // low selector
90  if (selector_start_ms != 0) {
91  uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
92  if (hold_time < 2000) {
93  // re-center the value
94  re_center();
95  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
96  } else if (hold_time < 5000) {
97  // change parameter
99  }
100  }
101  selector_start_ms = 0;
102  }
103 }
104 
105 /*
106  re-center the tuning value
107  */
109 {
110  AP_Float *f = get_param_pointer(current_parm);
111  if (f != nullptr) {
112  center_value = f->get();
113  }
114  mid_point_wait = true;
115 }
116 
117 /*
118  check for changed tuning input
119  */
120 void AP_Tuning::check_input(uint8_t flightmode)
121 {
122  if (channel <= 0 || parmset <= 0) {
123  // disabled
124  return;
125  }
126 
127  // check for revert on changed flightmode
128  if (flightmode != last_flightmode) {
129  if (need_revert != 0 && mode_revert != 0) {
130  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: reverted");
132  re_center();
133  }
134  last_flightmode = flightmode;
135  }
136 
137  // only adjust values at 10Hz
138  uint32_t now = AP_HAL::millis();
139  uint32_t dt_ms = now - last_check_ms;
140  if (dt_ms < 100) {
141  return;
142  }
143  last_check_ms = now;
144 
146  // not valid channel
147  return;
148  }
149 
150  // check for invalid range
151  if (range < 1.1f) {
152  range.set(1.1f);
153  }
154 
155  if (current_parm == 0) {
156  next_parameter();
157  }
158 
159  // cope with user changing parmset while tuning
160  if (current_set != parmset) {
161  re_center();
162  }
164 
166 
167  if (selector_start_ms) {
168  // no tuning while selector high
169  return;
170  }
171 
172  if (current_parm == 0) {
173  return;
174  }
175 
177  if (chan == nullptr) {
178  return;
179  }
180  float chan_value = linear_interpolate(-1, 1, chan->get_radio_in(), channel_min, channel_max);
181  if (dt_ms > 500) {
182  last_channel_value = chan_value;
183  }
184 
185  // check for controller error
187 
188  if (fabsf(chan_value - last_channel_value) < 0.01) {
189  // ignore changes of less than 1%
190  return;
191  }
192 
193  //hal.console->printf("chan_value %.2f last_channel_value %.2f\n", chan_value, last_channel_value);
194 
195  if (mid_point_wait) {
196  // see if we have crossed the mid-point. We use a small deadzone to make it easier
197  // to move to the "indent" portion of a slider to start tuning
198  const float dead_zone = 0.02;
199  if ((chan_value > dead_zone && last_channel_value > 0) ||
200  (chan_value < -dead_zone && last_channel_value < 0)) {
201  // still waiting
202  return;
203  }
204  // starting tuning
205  mid_point_wait = false;
206  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm));
208  }
209  last_channel_value = chan_value;
210 
211  float new_value;
212  if (chan_value > 0) {
213  new_value = linear_interpolate(center_value, range*center_value, chan_value, 0, 1);
214  } else {
215  new_value = linear_interpolate(center_value/range, center_value, chan_value, -1, 0);
216  }
217  changed = true;
218  need_revert |= (1U << current_parm_index);
219  set_value(current_parm, new_value);
220  Log_Write_Parameter_Tuning(new_value);
221 }
222 
223 
224 /*
225  log a tuning change
226  */
228 {
229  DataFlash_Class::instance()->Log_Write("PTUN", "TimeUS,Set,Parm,Value,CenterValue", "QBBff",
231  parmset,
232  current_parm,
233  (double)value,
234  (double)center_value);
235 }
236 
237 /*
238  save parameters in the set
239  */
241 {
242  uint8_t set = (uint8_t)parmset.get();
243  if (set < set_base) {
244  // single parameter tuning
245  save_value(set);
246  return;
247  }
248  // multiple parameter tuning
249  for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
250  if (tuning_sets[i].set+set_base == set) {
251  for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
252  save_value(tuning_sets[i].parms[p]);
253  }
254  break;
255  }
256  }
257 }
258 
259 
260 /*
261  save parameters in the set
262  */
264 {
265  uint8_t set = (uint8_t)parmset.get();
266  if (set < set_base) {
267  // single parameter tuning
268  reload_value(set);
269  return;
270  }
271  for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
272  if (tuning_sets[i].set+set_base == set) {
273  for (uint8_t p=0; p<tuning_sets[i].num_parms; p++) {
274  if (p >= 32 || (need_revert & (1U<<p))) {
275  reload_value(tuning_sets[i].parms[p]);
276  }
277  }
278  need_revert = 0;
279  break;
280  }
281  }
282 }
283 
284 /*
285  switch to the next parameter in the set
286  */
288 {
289  uint8_t set = (uint8_t)parmset.get();
290  if (set < set_base) {
291  // nothing to do but re-center
292  current_parm = set;
293  re_center();
294  return;
295  }
296  for (uint8_t i=0; tuning_sets[i].num_parms != 0; i++) {
297  if (tuning_sets[i].set+set_base == set) {
298  if (current_parm == 0) {
299  current_parm_index = 0;
300  } else {
301  current_parm_index = (current_parm_index + 1) % tuning_sets[i].num_parms;
302  }
304  re_center();
305  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm));
307  break;
308  }
309  }
310 }
311 
312 /*
313  return a string representing a tuning parameter
314  */
315 const char *AP_Tuning::get_tuning_name(uint8_t parm)
316 {
317  for (uint8_t i=0; tuning_names[i].name != nullptr; i++) {
318  if (parm == tuning_names[i].parm) {
319  return tuning_names[i].name;
320  }
321  }
322  return "UNKNOWN";
323 }
324 
325 /*
326  check for controller error
327  */
329 {
330  float err = controller_error(current_parm);
331  if (err > error_threshold) {
332  uint32_t now = AP_HAL::millis();
333  if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
335  gcs().send_text(MAV_SEVERITY_INFO, "Tuning: error %.2f", (double)err);
337  }
338  }
339 }
uint8_t current_set
Definition: AP_Tuning.h:72
bool get_soft_armed() const
Definition: Util.h:15
uint32_t last_check_ms
Definition: AP_Tuning.h:61
static uint8_t get_valid_channel_count(void)
uint32_t selector_start_ms
Definition: AP_Tuning.h:50
virtual float controller_error(uint8_t parm)=0
int16_t get_radio_in() const
Definition: RC_Channel.h:79
static RC_Channel * rc_channel(uint8_t chan)
Definition: RC_Channel.h:145
Interface definition for the various Ground Control System.
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void check_selector_switch(void)
Definition: AP_Tuning.cpp:62
AP_HAL::Util * util
Definition: HAL.h:115
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
GCS & gcs()
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
float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high)
Definition: AP_Math.cpp:81
uint8_t current_parm_index
Definition: AP_Tuning.h:69
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
void revert_parameters(void)
Definition: AP_Tuning.cpp:263
RC_Channel manager, with EEPROM-backed storage of constants.
AP_Int8 mode_revert
Definition: AP_Tuning.h:46
Object managing one RC channel.
Definition: RC_Channel.h:15
#define f(i)
uint32_t millis()
Definition: system.cpp:157
void check_controller_error(void)
Definition: AP_Tuning.cpp:328
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
const char * name
Definition: AP_Tuning.h:21
virtual void reload_value(uint8_t parm)=0
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
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
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
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
float value
bool changed
Definition: AP_Tuning.h:75
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_Int16 channel_min
Definition: AP_Tuning.h:42
uint8_t last_flightmode
Definition: AP_Tuning.h:81
static struct notify_events_type events
Definition: AP_Notify.h:118
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
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_Int8 selector
Definition: AP_Tuning.h:44
void next_parameter(void)
Definition: AP_Tuning.cpp:287