mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-10 00:23:57 -03:00
Sub: Increase threshold for input hold engaged flag
Also clear input hold offsets when they are below this threshold
This commit is contained in:
parent
14c593babf
commit
d25dd1d944
@ -320,11 +320,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
||||
break;
|
||||
case JSButton::button_function_t::k_input_hold_set:
|
||||
if (!held) {
|
||||
zTrim = z_last-500;
|
||||
xTrim = x_last;
|
||||
yTrim = y_last;
|
||||
zTrim = abs(z_last-500) > 50 ? z_last-500 : 0;
|
||||
xTrim = abs(x_last) > 50 ? x_last : 0;
|
||||
yTrim = abs(y_last) > 50 ? y_last : 0;
|
||||
input_hold_engaged = zTrim || xTrim || yTrim;
|
||||
gcs_send_text(MAV_SEVERITY_INFO,"#Input Hold Set");
|
||||
input_hold_engaged = abs(zTrim) > 20 || abs(xTrim) > 20 || abs(yTrim) > 20;
|
||||
}
|
||||
break;
|
||||
case JSButton::button_function_t::k_relay_1_on:
|
||||
|
Loading…
Reference in New Issue
Block a user