diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index bcd8e89a98..c644a3b3d2 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -196,12 +196,6 @@ void MAVLink_routing::forward(const mavlink_message_t* msg) */ void MAVLink_routing::handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t* msg) { - if (msg->compid == MAV_COMP_ID_GIMBAL) - { - //Mask out gimbal messages, since those are causing problems for the controller - return; - } - uint16_t mask = GCS_MAVLINK::active_channel_mask(); // don't send on the incoming channel. This should only matter if