mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: Update OSD on 5 percent change
This commit is contained in:
parent
64b4b2459b
commit
f73752c1f6
|
@ -218,6 +218,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
last_channel_value = chan_value;
|
||||
|
||||
float new_value;
|
||||
static float old_value;
|
||||
if (chan_value > 0) {
|
||||
new_value = linear_interpolate(center_value, range*center_value, chan_value, 0, 1);
|
||||
} else {
|
||||
|
@ -227,11 +228,14 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
need_revert |= (1U << current_parm_index);
|
||||
set_value(current_parm, new_value);
|
||||
|
||||
if ( fabsf(new_value-old_value) > (0.05 * old_value) ) {
|
||||
old_value = new_value;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
|
||||
"Tuning %s%s%0.5f",
|
||||
"Tuning %s%s%0.4f",
|
||||
get_tuning_name(current_parm),
|
||||
((chan_value < dead_zone) && (chan_value > -dead_zone)) ? "> " : ": ",
|
||||
(double)(new_value));
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
Log_Write_Parameter_Tuning(new_value);
|
||||
|
|
Loading…
Reference in New Issue