diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 1574fb2e84cfc8ca302425518c79c91f2c696159..b6178a6e16a526af2ad69a4f3981bf7a2945e58d 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -639,7 +639,8 @@ void MissionController::_recalcWaypointLines(void) // If we still haven't found the first coordinate item and we hit a a takeoff command link back to home if (firstCoordinateItem && item->isSimpleItem() && - qobject_cast(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) { + (qobject_cast(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || + qobject_cast(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) { linkBackToHome = true; } diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index fce51b800a7d265830cb3350b6c8cfa078055ddf..5dbec5851f95621e2abd90e469d264245e44b1b9 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -143,7 +143,6 @@ void MockLink::run(void) void MockLink::_run1HzTasks(void) { if (_mavlinkStarted && _connected) { - _sendHeartBeat(); _sendVibration(); if (!qgcApp()->runningUnitTests()) { // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation @@ -165,6 +164,7 @@ void MockLink::_run1HzTasks(void) void MockLink::_run10HzTasks(void) { if (_mavlinkStarted && _connected) { + _sendHeartBeat(); if (_sendGPSPositionDelayCount > 0) { // We delay gps position for better testing _sendGPSPositionDelayCount--; diff --git a/src/qgcunittest/MavlinkLogTest.cc b/src/qgcunittest/MavlinkLogTest.cc index 1953805cf514c9e98ce02d9b4b2baf78eee32e65..4a66ebf77dd8086bbdb6272a8c6840cf90ea486a 100644 --- a/src/qgcunittest/MavlinkLogTest.cc +++ b/src/qgcunittest/MavlinkLogTest.cc @@ -128,7 +128,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm) if (arm) { qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->setArmed(true); - QTest::qWait(1500); // Wait long enough for heartbeat to come through + QTest::qWait(500); // Wait long enough for heartbeat to come through // On Disconnect: We should get a getSaveFileName dialog. logSaveDir.setPath(QStandardPaths::writableLocation(QStandardPaths::TempLocation));