diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc index de06cccfff75035fcf8242e981923bc65f236883..b6b4793c986c890b73e172f3929b61459b9d0609 100644 --- a/src/MissionManager/MissionControllerTest.cc +++ b/src/MissionManager/MissionControllerTest.cc @@ -135,9 +135,8 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType) QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF); QCOMPARE(simpleItem->childItems()->count(), 0); - // If the first item added specifies a coordinate, then planned home position will be set - bool plannedHomePositionValue = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? false : true; - QCOMPARE(settingsItem->coordinate().isValid(), plannedHomePositionValue); + // Planned home position should always be set after first item + QVERIFY(settingsItem->coordinate().isValid()); // ArduPilot takeoff command has no coordinate, so should be child item QCOMPARE(settingsItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0);