From cf67b0a71a572c1b2baf46e821ad11cb4fe4613a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 6 Jun 2023 18:05:07 +1000 Subject: [PATCH] Rover: add option to disable relay and servorelay libraries --- Rover/Parameters.cpp | 2 ++ Rover/Rover.cpp | 2 ++ Rover/system.cpp | 2 ++ 3 files changed, 6 insertions(+) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index b2ae69aef5..5fb3ebf707 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -221,9 +221,11 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_Baro/AP_Baro.cpp GOBJECT(barometer, "BARO", AP_Baro), +#if AP_RELAY_ENABLED // @Group: RELAY_ // @Path: ../libraries/AP_Relay/AP_Relay.cpp GOBJECT(relay, "RELAY_", AP_Relay), +#endif // @Group: RCMAP_ // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 9e5ba4f93d..2a429dd555 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -96,7 +96,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200, 57), SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200, 60), SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300, 63), +#if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66), +#endif #if AP_GRIPPER_ENABLED SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69), #endif diff --git a/Rover/system.cpp b/Rover/system.cpp index bd6ed6b1cc..0f425c1606 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -107,7 +107,9 @@ void Rover::init_ardupilot() optflow.init(MASK_LOG_OPTFLOW); #endif // AP_OPTICALFLOW_ENABLED +#if AP_RELAY_ENABLED relay.init(); +#endif #if HAL_MOUNT_ENABLED // initialise camera mount