diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index f62437dc970d2d8889f3516b2236365580bc1509..02d1ba2b867b01fba2be14c6f4fee777e0840dd4 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -426,21 +426,21 @@ void MissionController::_initAllMissionItems(void) if (_activeVehicle && _activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && _missionItems->count() != 0) { homeItem = qobject_cast(_missionItems->get(0)); - homeItem->setHomePositionSpecialCase(true); } else { // Add the home position item to the front homeItem = new MissionItem(this); - homeItem->setHomePositionSpecialCase(true); - if (_activeVehicle) { - homeItem->setCoordinate(_activeVehicle->homePosition()); - homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable()); - } - homeItem->setCommand(MAV_CMD_NAV_WAYPOINT); - homeItem->setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT); homeItem->setSequenceNumber(0); _missionItems->insert(0, homeItem); } - homeItem->setHomePositionValid(false); + homeItem->setHomePositionSpecialCase(true); + if (_activeVehicle) { + homeItem->setCoordinate(_activeVehicle->homePosition()); + homeItem->setHomePositionValid(_activeVehicle->homePositionAvailable()); + } else { + homeItem->setHomePositionValid(false); + } + homeItem->setCommand(MAV_CMD_NAV_WAYPOINT); + homeItem->setFrame(MAV_FRAME_GLOBAL); for (int i=0; i<_missionItems->count(); i++) { _initMissionItem(qobject_cast(_missionItems->get(i))); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 925f9ab821e6ac084a7db1e28986a3e4d2e0f1d8..267fc1ae2172919e1ec465a01a55718ade7d0567 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -236,17 +236,18 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message) QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0, homePos.longitude / 10000000.0, homePos.altitude / 1000.0); - if (newHomePosition != _homePosition) { + if (!_homePositionAvailable || newHomePosition != _homePosition) { emitHomePositionChanged = true; _homePosition = newHomePosition; } if (!_homePositionAvailable) { emitHomePositionAvailableChanged = true; + _homePositionAvailable = true; } - _homePositionAvailable = true; if (emitHomePositionChanged) { + qCDebug(VehicleLog) << "New home position" << newHomePosition; emit homePositionChanged(_homePosition); } if (emitHomePositionAvailableChanged) { diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 4ca7c4a50eac915a53db1046f5b1d4292f553307..46ae7556b88f760bcb5794be50c8d1c7f59646bd 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -70,7 +70,7 @@ union px4_custom_mode { float MockLink::_vehicleLatitude = 47.633033f; float MockLink::_vehicleLongitude = -122.08794f; -float MockLink::_vehicleAltitude = 9872.5f; +float MockLink::_vehicleAltitude = 3.5f; const char* MockConfiguration::_firmwareTypeKey = "FirmwareType"; const char* MockConfiguration::_vehicleTypeKey = "VehicleType";