mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
ArduSub: add option to disable relay and servorelay libraries
This commit is contained in:
parent
9d3ebf0d54
commit
d9e89eb602
@ -252,7 +252,9 @@ void Sub::three_hz_loop()
|
|||||||
fence_check();
|
fence_check();
|
||||||
#endif // AP_FENCE_ENABLED
|
#endif // AP_FENCE_ENABLED
|
||||||
|
|
||||||
|
#if AP_SERVORELAYEVENTS_ENABLED
|
||||||
ServoRelayEvents.update_events();
|
ServoRelayEvents.update_events();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// one_hz_loop - runs at 1Hz
|
// one_hz_loop - runs at 1Hz
|
||||||
|
@ -409,9 +409,11 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
GOBJECT(camera, "CAM", AP_Camera),
|
GOBJECT(camera, "CAM", AP_Camera),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_RELAY_ENABLED
|
||||||
// @Group: RELAY_
|
// @Group: RELAY_
|
||||||
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
|
||||||
GOBJECT(relay, "RELAY_", AP_Relay),
|
GOBJECT(relay, "RELAY_", AP_Relay),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Group: COMPASS_
|
// @Group: COMPASS_
|
||||||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||||
|
@ -359,6 +359,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
|
|||||||
controls_reset_since_input_hold = !input_hold_engaged;
|
controls_reset_since_input_hold = !input_hold_engaged;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#if AP_RELAY_ENABLED
|
||||||
case JSButton::button_function_t::k_relay_1_on:
|
case JSButton::button_function_t::k_relay_1_on:
|
||||||
relay.on(0);
|
relay.on(0);
|
||||||
break;
|
break;
|
||||||
@ -423,10 +424,12 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held)
|
|||||||
relay.on(3);
|
relay.on(3);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////
|
////////////////////////////////////////////////
|
||||||
// Servo functions
|
// Servo functions
|
||||||
// TODO: initialize
|
// TODO: initialize
|
||||||
|
#if AP_SERVORELAYEVENTS_ENABLED
|
||||||
case JSButton::button_function_t::k_servo_1_inc:
|
case JSButton::button_function_t::k_servo_1_inc:
|
||||||
{
|
{
|
||||||
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
|
||||||
@ -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
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif // AP_SERVORELAYEVENTS_ENABLED
|
||||||
|
|
||||||
case JSButton::button_function_t::k_roll_pitch_toggle:
|
case JSButton::button_function_t::k_roll_pitch_toggle:
|
||||||
if (!held) {
|
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
|
// Act based on the function assigned to this button
|
||||||
switch (get_button(_button)->function(shift)) {
|
switch (get_button(_button)->function(shift)) {
|
||||||
|
#if AP_RELAY_ENABLED
|
||||||
case JSButton::button_function_t::k_relay_1_momentary:
|
case JSButton::button_function_t::k_relay_1_momentary:
|
||||||
relay.off(0);
|
relay.off(0);
|
||||||
break;
|
break;
|
||||||
@ -607,6 +612,8 @@ 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;
|
||||||
|
#endif
|
||||||
|
#if AP_SERVORELAYEVENTS_ENABLED
|
||||||
case JSButton::button_function_t::k_servo_1_min_momentary:
|
case JSButton::button_function_t::k_servo_1_min_momentary:
|
||||||
case JSButton::button_function_t::k_servo_1_max_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
|
ServoRelayEvents.do_set_servo(SERVO_CHAN_3, chan->get_trim()); // 1-indexed
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -70,7 +70,9 @@ void Sub::init_ardupilot()
|
|||||||
init_rc_out(); // sets up motors and output to escs
|
init_rc_out(); // sets up motors and output to escs
|
||||||
init_joystick(); // joystick initialization
|
init_joystick(); // joystick initialization
|
||||||
|
|
||||||
|
#if AP_RELAY_ENABLED
|
||||||
relay.init();
|
relay.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* setup the 'main loop is dead' check. Note that this relies on
|
* setup the 'main loop is dead' check. Note that this relies on
|
||||||
|
Loading…
Reference in New Issue
Block a user