|
|
|
@ -76,6 +76,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
@@ -76,6 +76,9 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
|
|
|
|
|
for (uint8_t i = 0 ; i < 16 ; i++) { |
|
|
|
|
if ((buttons & (1 << i))) { |
|
|
|
|
handle_jsbutton_press(i,shift,(buttons_prev & (1 << i))); |
|
|
|
|
// buttonDebounce = tnow_ms;
|
|
|
|
|
} else if (buttons_prev & (1 << i)) { |
|
|
|
|
handle_jsbutton_release(i, shift); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -347,6 +350,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@@ -347,6 +350,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|
|
|
|
relay.toggle(0); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_1_momentary: |
|
|
|
|
if (!held) { |
|
|
|
|
relay.on(0); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_2_on: |
|
|
|
|
relay.on(1); |
|
|
|
|
break; |
|
|
|
@ -358,6 +366,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@@ -358,6 +366,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|
|
|
|
relay.toggle(1); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_2_momentary: |
|
|
|
|
if (!held) { |
|
|
|
|
relay.on(1); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_3_on: |
|
|
|
|
relay.on(2); |
|
|
|
|
break; |
|
|
|
@ -369,6 +382,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@@ -369,6 +382,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|
|
|
|
relay.toggle(2); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_3_momentary: |
|
|
|
|
if (!held) { |
|
|
|
|
relay.on(2); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_4_on: |
|
|
|
|
relay.on(3); |
|
|
|
|
break; |
|
|
|
@ -380,6 +398,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@@ -380,6 +398,11 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|
|
|
|
relay.toggle(3); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_4_momentary: |
|
|
|
|
if (!held) { |
|
|
|
|
relay.on(3); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
////////////////////////////////////////////////
|
|
|
|
|
// Servo functions
|
|
|
|
@ -516,6 +539,25 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@@ -516,6 +539,25 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Sub::handle_jsbutton_release(uint8_t button, bool shift) { |
|
|
|
|
|
|
|
|
|
// Act based on the function assigned to this button
|
|
|
|
|
switch (get_button(button)->function(shift)) { |
|
|
|
|
case JSButton::button_function_t::k_relay_1_momentary: |
|
|
|
|
relay.off(0); |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_2_momentary: |
|
|
|
|
relay.off(1); |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_3_momentary: |
|
|
|
|
relay.off(2); |
|
|
|
|
break; |
|
|
|
|
case JSButton::button_function_t::k_relay_4_momentary: |
|
|
|
|
relay.off(3); |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
JSButton* Sub::get_button(uint8_t index) |
|
|
|
|
{ |
|
|
|
|
// Help to access appropriate parameter
|
|
|
|
|