Browse Source

Merge pull request #4138 from DonLakeFlyer/VTOLTakeoff

Fix line back to home for VTOL takeoff
QGC4.4
Don Gagne 9 years ago committed by GitHub
parent
commit
42f447cc61
  1. 3
      src/MissionManager/MissionController.cc
  2. 2
      src/comm/MockLink.cc
  3. 2
      src/qgcunittest/MavlinkLogTest.cc

3
src/MissionManager/MissionController.cc

@ -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 (firstCoordinateItem &&
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;
}

2
src/comm/MockLink.cc

@ -143,7 +143,6 @@ void MockLink::run(void) @@ -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) @@ -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--;

2
src/qgcunittest/MavlinkLogTest.cc

@ -128,7 +128,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm) @@ -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));

Loading…
Cancel
Save