Copter: Change the process for errors

This commit is contained in:
murata 2022-02-10 20:09:42 +09:00 committed by Tom Pittenger
parent 42d1ce635b
commit 926558a808

View File

@ -1401,17 +1401,19 @@ void GCS_MAVLINK_Copter::handleMessage(const 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)) {
if (!copter.set_home_to_current_location(true)) {
// silently ignored
}
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-result"
copter.set_home_to_current_location(true);
#pragma GCC diagnostic pop
} 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 (!copter.set_home(new_home_loc, true)) {
// silently ignored
}
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-result"
copter.set_home(new_home_loc, true);
#pragma GCC diagnostic pop
}
break;
}