Copter: remove redundant home-setting sanity checks

This commit is contained in:
Peter Barker 2019-02-13 13:47:01 +11:00 committed by Peter Barker
parent 1977123362
commit 13db459f49
2 changed files with 0 additions and 13 deletions

View File

@ -699,10 +699,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
if (!is_zero(packet.param1)) {
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);
@ -1253,10 +1249,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
// silently ignored
}
} else {
// 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;

View File

@ -58,11 +58,6 @@ bool Copter::set_home_to_current_location(bool lock) {
// returns true if home location set successfully
bool Copter::set_home(const Location& loc, bool lock)
{
// check location is valid
if (loc.lat == 0 && loc.lng == 0) {
return false;
}
// check EKF origin has been set
Location ekf_origin;
if (!ahrs.get_origin(ekf_origin)) {