Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove handling of MAVLINK_MSG_ID_SET_HOME_POSITION #20705

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
18 changes: 0 additions & 18 deletions ArduCopter/GCS_Mavlink.cpp
Expand Up @@ -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);
Expand Down
17 changes: 0 additions & 17 deletions ArduPlane/GCS_Mavlink.cpp
Expand Up @@ -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
Expand Down
22 changes: 0 additions & 22 deletions ArduSub/GCS_Mavlink.cpp
Expand Up @@ -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: {
Expand Down
15 changes: 0 additions & 15 deletions Blimp/GCS_Mavlink.cpp
Expand Up @@ -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;
Expand Down