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.
This commit is contained in:
Peter Barker 2022-05-06 10:50:26 +10:00 committed by Andrew Tridgell
parent 1764dce39e
commit 2f8b25328d
1 changed files with 0 additions and 15 deletions

View File

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