Commit 877b3cce authored by DonLakeFlyer's avatar DonLakeFlyer

Handle bogus lat/lon from ArduPilot

parent bc4ee574
......@@ -158,7 +158,10 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
qWarning() << "First item is not settings item";
return;
}
settingsItem->setCoordinate(newMissionItems[0]->coordinate());
MissionItem* fakeHomeItem = newMissionItems[0];
if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
settingsItem->setCoordinate(fakeHomeItem->coordinate());
}
i = 1;
}
......
......@@ -681,8 +681,8 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
mavlink_global_position_int_t globalPositionInt;
mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
// ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat/alt 0/0/0 even when it has not gps signal
if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0 && globalPositionInt.alt == 0) {
// ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has not gps signal
if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
return;
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment