From e20a6e7db6228ec063d3235d098079e2773d0a90 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 6 May 2022 10:50:25 +1000 Subject: [PATCH 1/4] ArduCopter: remove handling of MAVLINK_MSG_ID_SET_HOME_POSITION We decided to remove this after 4.2 was out in favour of MAV_CMD_DO_SET_HOME which has been available since 2015. The gcs-maintainers list was notified in Feburary. --- ArduCopter/GCS_Mavlink.cpp | 18 ------------------ 1 file changed, 18 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 1078f34e22ead..f7bcfcb7f2a7c 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1394,24 +1394,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) #endif break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: - { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - IGNORE_RETURN(copter.set_home_to_current_location(true)); - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - IGNORE_RETURN(copter.set_home(new_home_loc, true)); - } - break; - } - #if TOY_MODE_ENABLED == ENABLED case MAVLINK_MSG_ID_NAMED_VALUE_INT: copter.g2.toy_mode.handle_message(msg); From 8a97517d13a4e112901544279dc3ec797f2d6b0e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 6 May 2022 10:50:25 +1000 Subject: [PATCH 2/4] ArduPlane: remove handling of MAVLINK_MSG_ID_SET_HOME_POSITION We decided to remove this after 4.2 was out in favour of MAV_CMD_DO_SET_HOME which has been available since 2015. The gcs-maintainers list was notified in Feburary. --- ArduPlane/GCS_Mavlink.cpp | 17 ----------------- 1 file changed, 17 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 6a2c762c2b4bc..268279ca1a70e 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1232,23 +1232,6 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) break; } - case MAVLINK_MSG_ID_SET_HOME_POSITION: - { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - Location new_home_loc {}; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (!set_home(new_home_loc, false)) { - // silently fails... - break; - } - break; - } - case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // decode packet From fa293f3e7dfcf72a7a94a46f1e4feafda3ab04be Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 6 May 2022 10:50:25 +1000 Subject: [PATCH 3/4] ArduSub: remove handling of MAVLINK_MSG_ID_SET_HOME_POSITION We decided to remove this after 4.2 was out in favour of MAV_CMD_DO_SET_HOME which has been available since 2015. The gcs-maintainers list was notified in Feburary. --- ArduSub/GCS_Mavlink.cpp | 22 ---------------------- 1 file changed, 22 deletions(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index dd3df300ce63d..c120e1b016eff 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -718,28 +718,6 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) #endif break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - if (!sub.set_home_to_current_location(true)) { - // ignore this failure - } - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (sub.far_from_EKF_origin(new_home_loc)) { - break; - } - IGNORE_RETURN(sub.set_home(new_home_loc, true)); - } - break; - } - // This adds support for leak detectors in a separate enclosure // connected to a mavlink enabled subsystem case MAVLINK_MSG_ID_SYS_STATUS: { From 27077e1362bb9875fa8048450b0fc132af3bca4d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 6 May 2022 10:50:26 +1000 Subject: [PATCH 4/4] Blimp: remove handling of MAVLINK_MSG_ID_SET_HOME_POSITION We decided to remove this after 4.2 was out in favour of MAV_CMD_DO_SET_HOME which has been available since 2015. The gcs-maintainers list was notified in Feburary. --- Blimp/GCS_Mavlink.cpp | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 3601c5bf7fc6d..0d885bcc8aa27 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -538,21 +538,6 @@ void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_TERRAIN_CHECK: break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: { - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - IGNORE_RETURN(blimp.set_home_to_current_location(true)); - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - IGNORE_RETURN(blimp.set_home(new_home_loc, true)); - } - break; - } - default: handle_common_message(msg); break;