mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
Sub: Add momentary servo button function
This commit is contained in:
parent
dd239183c1
commit
8fec2cbea3
@ -424,12 +424,14 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_1_min:
|
case JSButton::button_function_t::k_servo_1_min:
|
||||||
|
case JSButton::button_function_t::k_servo_1_min_momentary:
|
||||||
{
|
{
|
||||||
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
|
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
|
||||||
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_min()); // 1-indexed
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_1_max:
|
case JSButton::button_function_t::k_servo_1_max:
|
||||||
|
case JSButton::button_function_t::k_servo_1_max_momentary:
|
||||||
{
|
{
|
||||||
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
|
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
|
||||||
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_output_max()); // 1-indexed
|
||||||
@ -459,12 +461,14 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_2_min:
|
case JSButton::button_function_t::k_servo_2_min:
|
||||||
|
case JSButton::button_function_t::k_servo_2_min_momentary:
|
||||||
{
|
{
|
||||||
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
|
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_2 - 1); // 0-indexed
|
||||||
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_min()); // 1-indexed
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_2_max:
|
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
|
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
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_2, chan->get_output_max()); // 1-indexed
|
||||||
@ -494,12 +498,14 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_3_min:
|
case JSButton::button_function_t::k_servo_3_min:
|
||||||
|
case JSButton::button_function_t::k_servo_3_min_momentary:
|
||||||
{
|
{
|
||||||
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
|
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_3 - 1); // 0-indexed
|
||||||
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_min()); // 1-indexed
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case JSButton::button_function_t::k_servo_3_max:
|
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
|
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
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_output_max()); // 1-indexed
|
||||||
@ -555,6 +561,27 @@ void Sub::handle_jsbutton_release(uint8_t button, bool shift) {
|
|||||||
case JSButton::button_function_t::k_relay_4_momentary:
|
case JSButton::button_function_t::k_relay_4_momentary:
|
||||||
relay.off(3);
|
relay.off(3);
|
||||||
break;
|
break;
|
||||||
|
case JSButton::button_function_t::k_servo_1_min_momentary:
|
||||||
|
case JSButton::button_function_t::k_servo_1_max_momentary:
|
||||||
|
{
|
||||||
|
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
|
||||||
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_1, chan->get_trim()); // 1-indexed
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case JSButton::button_function_t::k_servo_2_min_momentary:
|
||||||
|
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_trim()); // 1-indexed
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case JSButton::button_function_t::k_servo_3_min_momentary:
|
||||||
|
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_trim()); // 1-indexed
|
||||||
|
}
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user