Skip to content

Commit

Permalink
ArduSub: implement servo 2 and 3 min/max-toggle button functions
Browse files Browse the repository at this point in the history
  • Loading branch information
democat3457 authored and Williangalvani committed May 15, 2024
1 parent ce04c33 commit a9d4281
Showing 1 changed file with 40 additions and 0 deletions.
40 changes: 40 additions & 0 deletions ArduSub/joystick.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -525,13 +525,33 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_min_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_min()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_2_max:
case JSButton::button_function_t::k_servo_2_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_2_max_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_max()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_2_center:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
Expand Down Expand Up @@ -562,13 +582,33 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_min_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_min()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_3_max:
case JSButton::button_function_t::k_servo_3_max_momentary:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
}
break;
case JSButton::button_function_t::k_servo_3_max_toggle:
if(!held) {
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
if(chan->get_output_pwm() != chan->get_output_max()) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
} else {
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
}
break;
case JSButton::button_function_t::k_servo_3_center:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
Expand Down

0 comments on commit a9d4281

Please sign in to comment.