diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0ae1e3ce79..2d176c53c9 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4778,12 +4778,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_request_message(packet); break; +#if AP_SERVORELAYEVENTS_ENABLED case MAV_CMD_DO_SET_SERVO: case MAV_CMD_DO_REPEAT_SERVO: case MAV_CMD_DO_SET_RELAY: case MAV_CMD_DO_REPEAT_RELAY: result = handle_servorelay_message(packet); break; +#endif case MAV_CMD_DO_FLIGHTTERMINATION: result = handle_flight_termination(packet); diff --git a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp index e2e8a24a1d..65f949a00e 100644 --- a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp +++ b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp @@ -2,6 +2,8 @@ #include "AP_ServoRelayEvents/AP_ServoRelayEvents.h" +#if AP_SERVORELAYEVENTS_ENABLED + MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet) { AP_ServoRelayEvents *handler = AP::servorelayevents(); @@ -24,6 +26,7 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t & } break; +#if AP_RELAY_ENABLED case MAV_CMD_DO_SET_RELAY: if (handler->do_set_relay(packet.param1, packet.param2)) { result = MAV_RESULT_ACCEPTED; @@ -35,6 +38,7 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t & result = MAV_RESULT_ACCEPTED; } break; +#endif default: result = MAV_RESULT_UNSUPPORTED; @@ -43,3 +47,5 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t & return result; } + +#endif