diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 52da7be892..e8759ae502 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -965,30 +965,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) } break; - case MAV_CMD_DO_SET_SERVO: - if (rover.ServoRelayEvents.do_set_servo(packet.param1, packet.param2)) { - result = MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_REPEAT_SERVO: - if (rover.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 (rover.ServoRelayEvents.do_set_relay(packet.param1, packet.param2)) { - result = MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_REPEAT_RELAY: - if (rover.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)) { // when packet.param1 == 3 we reboot to hold in bootloader @@ -1560,6 +1536,11 @@ bool GCS_MAVLINK_Rover::accept_packet(const mavlink_status_t &status, mavlink_me return (msg.sysid == rover.g.sysid_my_gcs); } +AP_ServoRelayEvents *GCS_MAVLINK_Rover::get_servorelayevents() const +{ + return &rover.ServoRelayEvents; +} + AP_Mission *GCS_MAVLINK_Rover::get_mission() { return &rover.mission; diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index 541e9fcf45..0d01bde94f 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -18,6 +18,7 @@ protected: AP_Mission *get_mission() override; AP_Rally *get_rally() const override { return nullptr; }; + AP_ServoRelayEvents *get_servorelayevents() const override; uint8_t sysid_my_gcs() const override;