From cd8a6996756d17a8fb4e9a0b893640a37c7abab4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 6 Jun 2023 18:05:07 +1000 Subject: [PATCH] ArduCopter: add option to disable relay and servorelay libraries --- ArduCopter/Copter.cpp | 2 ++ ArduCopter/Parameters.cpp | 2 ++ ArduCopter/system.cpp | 2 ++ 3 files changed, 6 insertions(+) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index dbb3357f5c..b9d47f9afe 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -178,7 +178,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK_CLASS(AC_Sprayer, &copter.sprayer, update, 3, 90, 54), #endif SCHED_TASK(three_hz_loop, 3, 75, 57), +#if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), +#endif SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), #if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 69), diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 901e265fbf..95c362ea17 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -449,9 +449,11 @@ const AP_Param::Info Copter::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 #if PARACHUTE == ENABLED // @Group: CHUTE_ diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 4e1527e2fc..cf0431658f 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -92,7 +92,9 @@ void Copter::init_ardupilot() // motors initialised so parameters can be sent ap.initialised_params = true; +#if AP_RELAY_ENABLED relay.init(); +#endif /* * setup the 'main loop is dead' check. Note that this relies on