ArduSub: add option to disable relay and servorelay libraries

This commit is contained in:
Peter Barker 2023-06-06 18:05:07 +10:00 committed by Peter Barker
parent 9d3ebf0d54
commit d9e89eb602
4 changed files with 14 additions and 0 deletions

View File

@ -252,7 +252,9 @@ void Sub::three_hz_loop()
fence_check();
#endif // AP_FENCE_ENABLED
#if AP_SERVORELAYEVENTS_ENABLED
ServoRelayEvents.update_events();
#endif
}
// one_hz_loop - runs at 1Hz

View File

@ -409,9 +409,11 @@ const AP_Param::Info Sub::var_info[] = {
GOBJECT(camera, "CAM", AP_Camera),
#endif
#if AP_RELAY_ENABLED
// @Group: RELAY_
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT(relay, "RELAY_", AP_Relay),
#endif
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/AP_Compass.cpp

View File

@ -359,6 +359,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
controls_reset_since_input_hold = !input_hold_engaged;
}
break;
#if AP_RELAY_ENABLED
case JSButton::button_function_t::k_relay_1_on:
relay.on(0);
break;
@ -423,10 +424,12 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
relay.on(3);
}
break;
#endif
////////////////////////////////////////////////
// Servo functions
// TODO: initialize
#if AP_SERVORELAYEVENTS_ENABLED
case JSButton::button_function_t::k_servo_1_inc:
{
SRV_Channel* chan = SRV_Channels::srv_channel(SERVO_CHAN_1 - 1); // 0-indexed
@ -557,6 +560,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
break;
#endif // AP_SERVORELAYEVENTS_ENABLED
case JSButton::button_function_t::k_roll_pitch_toggle:
if (!held) {
@ -595,6 +599,7 @@ 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)) {
#if AP_RELAY_ENABLED
case JSButton::button_function_t::k_relay_1_momentary:
relay.off(0);
break;
@ -607,6 +612,8 @@ void Sub::handle_jsbutton_release(uint8_t _button, bool shift) {
case JSButton::button_function_t::k_relay_4_momentary:
relay.off(3);
break;
#endif
#if AP_SERVORELAYEVENTS_ENABLED
case JSButton::button_function_t::k_servo_1_min_momentary:
case JSButton::button_function_t::k_servo_1_max_momentary:
{
@ -628,6 +635,7 @@ void Sub::handle_jsbutton_release(uint8_t _button, bool shift) {
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
}
break;
#endif
}
}

View File

@ -70,7 +70,9 @@ void Sub::init_ardupilot()
init_rc_out(); // sets up motors and output to escs
init_joystick(); // joystick initialization
#if AP_RELAY_ENABLED
relay.init();
#endif
/*
* setup the 'main loop is dead' check. Note that this relies on