Browse Source

Merge pull request #5229 from DonLakeFlyer/HomePositionFixes

Home position update fixes
QGC4.4
Gus Grubba 8 years ago committed by GitHub
parent
commit
7efc47f186
  1. 10
      src/MissionManager/MissionController.cc
  2. 2
      src/MissionManager/MissionSettingsItem.cc

10
src/MissionManager/MissionController.cc

@ -1293,8 +1293,8 @@ void MissionController::_initAllVisualItems(void) @@ -1293,8 +1293,8 @@ void MissionController::_initAllVisualItems(void)
_settingsItem->setIsCurrentItem(true);
}
if (!_editMode && _controllerVehicle) {
_settingsItem->setCoordinate(_controllerVehicle->homePosition());
if (!_editMode && _managerVehicle->homePosition().isValid()) {
_settingsItem->setCoordinate(_managerVehicle->homePosition());
}
connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
@ -1481,6 +1481,8 @@ void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, boo @@ -1481,6 +1481,8 @@ void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, boo
{
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;
visualItems->insert(0, settingsItem);
if (addToCenter) {
@ -1515,8 +1517,8 @@ void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, boo @@ -1515,8 +1517,8 @@ void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, boo
settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
}
}
} else {
settingsItem->setCoordinate(_controllerVehicle->homePosition());
} else if (_managerVehicle->homePosition().isValid()) {
settingsItem->setCoordinate(_managerVehicle->homePosition());
}
}

2
src/MissionManager/MissionSettingsItem.cc

@ -221,7 +221,7 @@ void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate) @@ -221,7 +221,7 @@ void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
{
if (_plannedHomePositionCoordinate != coordinate) {
// ArduPilot tends to send crap home positions at initial vehicel boot, discard them
if (coordinate.latitude() != 0 || coordinate.longitude() != 0) {
if (coordinate.isValid() && (coordinate.latitude() != 0 || coordinate.longitude() != 0)) {
qDebug() << "Setting home position" << coordinate;
_plannedHomePositionCoordinate = coordinate;
emit coordinateChanged(coordinate);

Loading…
Cancel
Save