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.
This commit is contained in:
Peter Barker 2022-05-06 10:50:25 +10:00 committed by Andrew Tridgell
parent 7850aea186
commit c789755372

View File

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