From 507117bd8f70a7247a22cf7d32f167ca0b98e88b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 10 Dec 2014 14:04:10 +1100 Subject: [PATCH] Plane: removed use of mavlink_check_target() --- ArduPlane/GCS_Mavlink.pde | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 8283cd14d7..fd36e9be29 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1009,7 +1009,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // decode mavlink_command_long_t packet; mavlink_msg_command_long_decode(msg, &packet); - if (mavlink_check_target(packet.target_system, packet.target_component)) break; uint8_t result = MAV_RESULT_UNSUPPORTED; @@ -1340,8 +1339,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_FENCE_POINT: { mavlink_fence_point_t packet; mavlink_msg_fence_point_decode(msg, &packet); - if (mavlink_check_target(packet.target_system, packet.target_component)) - break; if (g.fence_action != FENCE_ACTION_NONE) { send_text_P(SEVERITY_LOW,PSTR("fencing must be disabled")); } else if (packet.count != g.fence_total) { @@ -1359,8 +1356,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_FENCE_FETCH_POINT: { mavlink_fence_fetch_point_t packet; mavlink_msg_fence_fetch_point_decode(msg, &packet); - if (mavlink_check_target(packet.target_system, packet.target_component)) - break; if (packet.idx >= g.fence_total) { send_text_P(SEVERITY_LOW,PSTR("bad fence point")); } else { @@ -1376,8 +1371,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_RALLY_POINT: { mavlink_rally_point_t packet; mavlink_msg_rally_point_decode(msg, &packet); - if (mavlink_check_target(packet.target_system, packet.target_component)) - break; if (packet.idx >= rally.get_rally_total() || packet.idx >= rally.get_rally_max()) { @@ -1405,8 +1398,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_RALLY_FETCH_POINT: { mavlink_rally_fetch_point_t packet; mavlink_msg_rally_fetch_point_decode(msg, &packet); - if (mavlink_check_target(packet.target_system, packet.target_component)) - break; if (packet.idx > rally.get_rally_total()) { send_text_P(SEVERITY_LOW, PSTR("bad rally point index")); break; @@ -1441,10 +1432,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) int16_t v[8]; mavlink_msg_rc_channels_override_decode(msg, &packet); - // exit immediately if this command is not meant for this vehicle - if (mavlink_check_target(packet.target_system,packet.target_component)) - break; - v[0] = packet.chan1_raw; v[1] = packet.chan2_raw; v[2] = packet.chan3_raw;