Copter: ensure Ch6 tuned value does not go out of range

This commit is contained in:
Robert Lefebvre 2015-12-29 17:39:57 -05:00 committed by Randy Mackay
parent e2879b375d
commit dc1846447e

View File

@ -16,8 +16,11 @@ void Copter::tuning() {
return;
}
float tuning_value = (float)g.rc_6.control_in / 1000.0f;
// set tuning range and then get new value
g.rc_6.set_range(g.radio_tuning_low,g.radio_tuning_high);
float tuning_value = (float)g.rc_6.control_in / 1000.0f;
// Tuning Value should never be outside the bounds of the specified low and high value
tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f);
Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g.rc_6.control_in, g.radio_tuning_low, g.radio_tuning_high);