Commit 53611b9c authored by DonLakeFlyer's avatar DonLakeFlyer

Discard bogus home position

parent dd4f3e70
......@@ -220,10 +220,14 @@ void MissionSettingsItem::_setDirty(void)
void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
{
if (_plannedHomePositionCoordinate != coordinate) {
_plannedHomePositionCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit exitCoordinateChanged(coordinate);
_plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
// ArduPilot tends to send crap home positions at initial vehicel boot, discard them
if (coordinate.latitude() != 0 || coordinate.longitude() != 0) {
qDebug() << "Setting home position" << coordinate;
_plannedHomePositionCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit exitCoordinateChanged(coordinate);
_plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
}
}
}
......
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