Plane: remove redundant home-setting sanity checks

This commit is contained in:
Peter Barker 2019-02-13 13:55:35 +11:00 committed by Peter Barker
parent dffc5568fe
commit 0c880a4c3e

View File

@ -982,14 +982,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
if (!is_zero(packet.param1)) {
return MAV_RESULT_FAILED;
}
if (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7)) {
// don't allow the 0,0 position
return MAV_RESULT_FAILED;
}
// sanity check location
if (!check_latlng(packet.param5,packet.param6)) {
return MAV_RESULT_FAILED;
}
Location new_home_loc {};
new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
@ -1294,14 +1286,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
{
mavlink_set_home_position_t packet;
mavlink_msg_set_home_position_decode(msg, &packet);
if((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) {
// don't allow the 0,0 position
break;
}
// sanity check location
if (!check_latlng(packet.latitude,packet.longitude)) {
break;
}
Location new_home_loc {};
new_home_loc.lat = packet.latitude;
new_home_loc.lng = packet.longitude;