Commit 42f447cc authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4138 from DonLakeFlyer/VTOLTakeoff

Fix line back to home for VTOL takeoff
parents 1749b2a1 ef7f6002
...@@ -639,7 +639,8 @@ void MissionController::_recalcWaypointLines(void) ...@@ -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 we still haven't found the first coordinate item and we hit a a takeoff command link back to home
if (firstCoordinateItem && if (firstCoordinateItem &&
item->isSimpleItem() && item->isSimpleItem() &&
qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) { (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
linkBackToHome = true; linkBackToHome = true;
} }
......
...@@ -143,7 +143,6 @@ void MockLink::run(void) ...@@ -143,7 +143,6 @@ void MockLink::run(void)
void MockLink::_run1HzTasks(void) void MockLink::_run1HzTasks(void)
{ {
if (_mavlinkStarted && _connected) { if (_mavlinkStarted && _connected) {
_sendHeartBeat();
_sendVibration(); _sendVibration();
if (!qgcApp()->runningUnitTests()) { if (!qgcApp()->runningUnitTests()) {
// Sending RC Channels during unit test breaks RC tests which does it's own RC simulation // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
...@@ -165,6 +164,7 @@ void MockLink::_run1HzTasks(void) ...@@ -165,6 +164,7 @@ void MockLink::_run1HzTasks(void)
void MockLink::_run10HzTasks(void) void MockLink::_run10HzTasks(void)
{ {
if (_mavlinkStarted && _connected) { if (_mavlinkStarted && _connected) {
_sendHeartBeat();
if (_sendGPSPositionDelayCount > 0) { if (_sendGPSPositionDelayCount > 0) {
// We delay gps position for better testing // We delay gps position for better testing
_sendGPSPositionDelayCount--; _sendGPSPositionDelayCount--;
......
...@@ -128,7 +128,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm) ...@@ -128,7 +128,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm)
if (arm) { if (arm) {
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->setArmed(true); 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. // On Disconnect: We should get a getSaveFileName dialog.
logSaveDir.setPath(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); logSaveDir.setPath(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
......
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