ArduCopter: 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 9b2dba95d0
commit cd8a699675
3 changed files with 6 additions and 0 deletions

View File

@ -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),

View File

@ -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_

View File

@ -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