diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 1ffb5f0419..a50c38f02b 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1269,30 +1269,6 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg) } break; - case MAV_CMD_DO_SET_SERVO: - if (sub.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) { - result = MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_REPEAT_SERVO: - if (sub.ServoRelayEvents.do_repeat_servo(packet.param1, packet.param2, packet.param3, packet.param4*1000)) { - result = MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_SET_RELAY: - if (sub.ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) { - result = MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_REPEAT_RELAY: - if (sub.ServoRelayEvents.do_repeat_relay(packet.param1, packet.param2, packet.param3*1000)) { - result = MAV_RESULT_ACCEPTED; - } - break; - case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) { // Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short @@ -1753,6 +1729,11 @@ AP_Mission *GCS_MAVLINK_Sub::get_mission() return &sub.mission; } +AP_ServoRelayEvents *GCS_MAVLINK_Sub::get_servorelayevents() const +{ + return &sub.ServoRelayEvents; +} + AP_Rally *GCS_MAVLINK_Sub::get_rally() const { #if AC_RALLY == ENABLED diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 845021c4fa..05f8bb696b 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -16,6 +16,7 @@ protected: AP_Mission *get_mission() override; AP_Rally *get_rally() const override; + AP_ServoRelayEvents *get_servorelayevents() const override; uint8_t sysid_my_gcs() const override;