mirror of https://github.com/ArduPilot/ardupilot
Blimp: Change the process for errors
This commit is contained in:
parent
e52931c692
commit
b76d048a5e
|
@ -542,17 +542,13 @@ void GCS_MAVLINK_Blimp::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 (!blimp.set_home_to_current_location(true)) {
|
||||
// silently ignored
|
||||
}
|
||||
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;
|
||||
if (!blimp.set_home(new_home_loc, true)) {
|
||||
// silently ignored
|
||||
}
|
||||
IGNORE_RETURN(blimp.set_home(new_home_loc, true));
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue