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.
This commit is contained in:
Peter Barker 2022-05-06 10:50:25 +10:00 committed by Andrew Tridgell
parent c789755372
commit 6152b8618f
1 changed files with 0 additions and 17 deletions

View File

@ -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