QGCXPlaneLink.cc 24.1 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file QGCXPlaneLink.cc
 *   Implementation of X-Plane interface
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QTimer>
#include <QList>
#include <QDebug>
#include <QMutexLocker>
35
#include <QNetworkInterface>
36 37 38 39
#include <iostream>
#include "QGCXPlaneLink.h"
#include "QGC.h"
#include <QHostInfo>
40
#include "UAS.h"
41 42
#include "MainWindow.h"

43
QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress localHost, quint16 localPort) :
44 45
    mav(mav),
    socket(NULL),
46 47 48
    process(NULL),
    terraSync(NULL)
{
49 50
    this->localHost = localHost;
    this->localPort = localPort/*+mav->getUASID()*/;
51
    this->connectState = false;
52
    this->name = tr("X-Plane Link (localPort:%1)").arg(localPort);
53 54 55 56
    setRemoteHost(remoteHost);
}

QGCXPlaneLink::~QGCXPlaneLink()
57 58 59 60
{
//    if(connectState) {
//       disconnectSimulation();
//    }
61 62 63 64 65 66 67 68 69 70 71
}

/**
 * @brief Runs the thread
 *
 **/
void QGCXPlaneLink::run()
{
    exec();
}

72
void QGCXPlaneLink::setPort(int localPort)
73
{
74
    this->localPort = localPort;
75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
    disconnectSimulation();
    connectSimulation();
}

void QGCXPlaneLink::processError(QProcess::ProcessError err)
{
    switch(err)
    {
    case QProcess::FailedToStart:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::Crashed:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Crashed"), tr("This is a X-Plane-related problem. Please upgrade X-Plane"));
        break;
    case QProcess::Timedout:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Start Timed Out"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::WriteError:
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with X-Plane"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::ReadError:
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with X-Plane"), tr("Please check if the path and command is correct"));
        break;
    case QProcess::UnknownError:
    default:
        MainWindow::instance()->showCriticalMessage(tr("X-Plane Error"), tr("Please check if the path and command is correct."));
        break;
    }
}

/**
106
 * @param localHost Hostname in standard formatting, e.g. locallocalHost:14551 or 192.168.1.1:14551
107
 */
108
void QGCXPlaneLink::setRemoteHost(const QString& localHost)
109
{
110
    if (localHost.contains(":"))
111
    {
112 113
        //qDebug() << "HOST: " << localHost.split(":").first();
        QHostInfo info = QHostInfo::fromName(localHost.split(":").first());
114 115
        if (info.error() == QHostInfo::NoError)
        {
116 117
            // Add localHost
            QList<QHostAddress> localHostAddresses = info.addresses();
118
            QHostAddress address;
119
            for (int i = 0; i < localHostAddresses.size(); i++)
120 121
            {
                // Exclude loopback IPv4 and all IPv6 addresses
122
                if (!localHostAddresses.at(i).toString().contains(":"))
123
                {
124
                    address = localHostAddresses.at(i);
125 126
                }
            }
127
            remoteHost = address;
128
            //qDebug() << "Address:" << address.toString();
129 130
            // Set localPort according to user input
            remotePort = localHost.split(":").last().toInt();
131 132 133 134
        }
    }
    else
    {
135
        QHostInfo info = QHostInfo::fromName(localHost);
136 137
        if (info.error() == QHostInfo::NoError)
        {
138 139
            // Add localHost
            remoteHost = info.addresses().first();
140 141 142
        }
    }

143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160
    //    // Send request to send correct data
    //#pragma pack(push, 1)
    //    struct payload {
    //        char b[5];
    //        int index;
    //        float f[8];
    //    } p;
    //#pragma pack(pop)

    //    p.b[0] = 'D';
    //    p.b[1] = 'A';
    //    p.b[2] = 'T';
    //    p.b[3] = 'A';
    //    p.b[4] = '\0';

    //    p.f[0]

    //    writeBytes((const char*)&p, sizeof(p));
161 162 163 164 165
}

void QGCXPlaneLink::updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
{

166 167 168 169 170 171 172 173 174 175 176 177 178 179 180
    #pragma pack(push, 1)
    struct payload {
        char b[5];
        int index;
        float f[8];
    } p;
    #pragma pack(pop)

    p.b[0] = 'D';
    p.b[1] = 'A';
    p.b[2] = 'T';
    p.b[3] = 'A';
    p.b[4] = '\0';

    p.index = 12;
181 182
    p.f[0] = pitchElevator;
    p.f[1] = rollAilerons;
183 184
    p.f[2] = yawRudder;

185 186 187 188
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);

189 190
    // Ail / Elevon / Rudder
    writeBytes((const char*)&p, sizeof(p));
191 192
    p.index = 8;
    writeBytes((const char*)&p, sizeof(p));
193 194 195

    p.index = 25;
    memset(p.f, 0, sizeof(p.f));
196 197 198 199
    p.f[0] = throttle;
    p.f[1] = throttle;
    p.f[2] = throttle;
    p.f[3] = throttle;
200 201
    // Throttle
    writeBytes((const char*)&p, sizeof(p));
202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
}

void QGCXPlaneLink::writeBytes(const char* data, qint64 size)
{
    //#define QGCXPlaneLink_DEBUG
#if 1
    QString bytes;
    QString ascii;
    for (int i=0; i<size; i++)
    {
        unsigned char v = data[i];
        bytes.append(QString().sprintf("%02x ", v));
        if (data[i] > 31 && data[i] < 127)
        {
            ascii.append(data[i]);
        }
        else
        {
            ascii.append(219);
        }
    }
223 224 225
    //qDebug() << "Sent" << size << "bytes to" << remoteHost.toString() << ":" << remotePort << "data:";
    //qDebug() << bytes;
    //qDebug() << "ASCII:" << ascii;
226
#endif
227
    if (connectState && socket) socket->writeDatagram(data, size, remoteHost, remotePort);
228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248
}

/**
 * @brief Read a number of bytes from the interface.
 *
 * @param data Pointer to the data byte array to write the bytes to
 * @param maxLength The maximum number of bytes to write
 **/
void QGCXPlaneLink::readBytes()
{
    const qint64 maxLength = 65536;
    char data[maxLength];
    QHostAddress sender;
    quint16 senderPort;

    unsigned int s = socket->pendingDatagramSize();
    if (s > maxLength) std::cerr << __FILE__ << __LINE__ << " UDP datagram overflow, allowed to read less bytes than datagram size" << std::endl;
    socket->readDatagram(data, maxLength, &sender, &senderPort);

    QByteArray b(data, s);

249 250
    /*// Print string
    QString state(b)*/;
251

252 253 254
    // Calculate the number of data segments a 36 bytes
    // XPlane always has 5 bytes header: 'DATA@'
    unsigned nsegs = (s-5)/36;
255

256
    //qDebug() << "XPLANE:" << "LEN:" << s << "segs:" << nsegs;
257

258 259 260 261 262 263
    #pragma pack(push, 1)
    struct payload {
        int index;
        float f[8];
    } p;
    #pragma pack(pop)
264

265 266 267 268 269 270 271 272 273 274 275 276 277 278
    if (data[0] == 'D' &&
            data[1] == 'A' &&
            data[2] == 'T' &&
            data[3] == 'A')
    {

        for (unsigned i = 0; i < nsegs; i++)
        {
            // Get index
            unsigned ioff = (5+i*36);;
            memcpy(&(p), data+ioff, sizeof(p));

            if (p.index == 3)
            {
279 280 281
                airspeed = p.f[6] * 0.44704f;
                groundspeed = p.f[7] * 0.44704;

282 283 284 285 286 287 288 289 290 291
                //qDebug() << "SPEEDS:" << "airspeed" << airspeed << "m/s, groundspeed" << groundspeed << "m/s";
            }
            else if (p.index == 8)
            {
                //qDebug() << "MAN:" << p.f[0] << p.f[3] << p.f[7];
                man_roll = p.f[0];
                man_pitch = p.f[1];
                man_yaw = p.f[2];
                UAS* uas = dynamic_cast<UAS*>(mav);
                if (uas) uas->setManualControlCommands(man_roll, man_pitch, man_yaw, 0.6);
292 293
            }
            else if (p.index == 16)
294
            {
295
                //qDebug() << "ANG VEL:" << p.f[0] << p.f[3] << p.f[7];
296 297 298
                rollspeed = p.f[2];
                pitchspeed = p.f[1];
                yawspeed = p.f[0];
299
            }
300
            else if (p.index == 17)
301
            {
302
                //qDebug() << "HDNG" << "pitch" << p.f[0] << "roll" << p.f[1] << "hding true" << p.f[2] << "hding mag" << p.f[3];
303 304
                pitch = p.f[0] / 180.0f * M_PI;
                roll = p.f[1] / 180.0f * M_PI;
305
                yaw = (p.f[2] - 180.0f) / 180.0f * M_PI;
306
            }
307

308 309 310 311 312
//            else if (p.index == 19)
//            {
//                qDebug() << "ATT:" << p.f[0] << p.f[1] << p.f[2];
//            }
            else if (p.index == 20)
313
            {
314
                //qDebug() << "LAT/LON/ALT:" << p.f[0] << p.f[1] << p.f[2];
315 316
                lat = p.f[0];
                lon = p.f[1];
317 318 319 320
                alt = p.f[2] * 0.3048f; // convert feet (MSL) to meters
            }
            else if (p.index == 12)
            {
321
                //qDebug() << "AIL/ELEV/RUD" << p.f[0] << p.f[1] << p.f[2];
322 323 324
            }
            else if (p.index == 25)
            {
325
                //qDebug() << "THROTTLE" << p.f[0] << p.f[1] << p.f[2] << p.f[3];
326 327 328
            }
            else if (p.index == 0)
            {
329
                //qDebug() << "STATS" << "fgraphics/s" << p.f[0] << "fsim/s" << p.f[2] << "t frame" << p.f[3] << "cpu load" << p.f[4] << "grnd ratio" << p.f[5] << "filt ratio" << p.f[6];
330 331 332
            }
            else if (p.index == 11)
            {
333
                //qDebug() << "CONTROLS" << "ail" << p.f[0] << "elev" << p.f[1] << "rudder" << p.f[2] << "nwheel" << p.f[3];
334 335 336
            }
            else
            {
337
                //qDebug() << "UNKNOWN #" << p.index << p.f[0] << p.f[1] << p.f[2] << p.f[3];
338 339
            }
        }
340 341 342 343 344 345 346 347 348 349 350 351 352 353
    }
    else if (data[0] == 'S' &&
             data[1] == 'N' &&
             data[2] == 'A' &&
             data[3] == 'P')
    {

    }
    else if (data[0] == 'S' &&
               data[1] == 'T' &&
               data[2] == 'A' &&
               data[3] == 'T')
    {

354 355 356 357 358
    }
    else
    {
        qDebug() << "UNKNOWN PACKET:" << data;
    }
359 360 361

    // Send updated state
    emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
362 363
                         pitchspeed, yawspeed, lat*1E7, lon*1E7, alt*1E3,
                         vx, vy, vz, xacc*1000, yacc*1000, zacc*1000);
364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393

    //    // Echo data for debugging purposes
    //    std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl;
    //    int i;
    //    for (i=0; i<s; i++)
    //    {
    //        unsigned int v=data[i];
    //        fprintf(stderr,"%02x ", v);
    //    }
    //    std::cerr << std::endl;
}


/**
 * @brief Get the number of bytes to read.
 *
 * @return The number of bytes to read
 **/
qint64 QGCXPlaneLink::bytesAvailable()
{
    return socket->pendingDatagramSize();
}

/**
 * @brief Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection couldn't be disconnected.
 **/
bool QGCXPlaneLink::disconnectSimulation()
{
394 395
    if (!connectState) return true;

396 397
    connectState = false;

398
    if (process) disconnect(process, SIGNAL(error(QProcess::ProcessError)),
399
               this, SLOT(processError(QProcess::ProcessError)));
400 401 402 403
    if (mav)
    {
        disconnect(mav, SIGNAL(hilControlsChanged(uint64_t, float, float, float, float, uint8_t, uint8_t)), this, SLOT(updateControls(uint64_t,float,float,float,float,uint8_t,uint8_t)));
        disconnect(this, SIGNAL(hilStateChanged(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)), mav, SLOT(sendHilState(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)));
404 405 406 407 408
        UAS* uas = dynamic_cast<UAS*>(mav);
        if (uas)
        {
            uas->stopHil();
        }
409
    }
410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434

    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
    if (terraSync)
    {
        terraSync->close();
        delete terraSync;
        terraSync = NULL;
    }
    if (socket)
    {
        socket->close();
        delete socket;
        socket = NULL;
    }

    emit simulationDisconnected();
    emit simulationConnected(false);
    return !connectState;
}

435 436 437 438 439 440 441
void QGCXPlaneLink::selectPlane(const QString& plane)
{

}

void QGCXPlaneLink::setPositionAttitude(double lat, double lon, double alt, double roll, double pitch, double yaw)
{
442
    #pragma pack(push, 1)
443 444
    struct VEH1_struct
    {
445
        char header[5];
446 447 448 449 450
        quint32 p;
        double lat_lon_ele[3];
        float psi_the_phi[3];
        float gear_flap_vect[3];
    } pos;
451
    #pragma pack(pop)
452

453 454 455 456 457
    pos.header[0] = 'V';
    pos.header[1] = 'E';
    pos.header[2] = 'H';
    pos.header[3] = '1';
    pos.header[4] = '0';
458 459 460 461
    pos.p = 0;
    pos.lat_lon_ele[0] = lat;
    pos.lat_lon_ele[1] = lon;
    pos.lat_lon_ele[2] = alt;
462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487
    pos.psi_the_phi[0] = roll;
    pos.psi_the_phi[1] = pitch;
    pos.psi_the_phi[2] = yaw;
    pos.gear_flap_vect[0] = 0.0f;
    pos.gear_flap_vect[1] = 0.0f;
    pos.gear_flap_vect[2] = 0.0f;

    writeBytes((const char*)&pos, sizeof(pos));

//    pos.header[0] = 'V';
//    pos.header[1] = 'E';
//    pos.header[2] = 'H';
//    pos.header[3] = '1';
//    pos.header[4] = '0';
//    pos.p = 0;
//    pos.lat_lon_ele[0] = -999;
//    pos.lat_lon_ele[1] = -999;
//    pos.lat_lon_ele[2] = -999;
//    pos.psi_the_phi[0] = -999;
//    pos.psi_the_phi[1] = -999;
//    pos.psi_the_phi[2] = -999;
//    pos.gear_flap_vect[0] = -999;
//    pos.gear_flap_vect[1] = -999;
//    pos.gear_flap_vect[2] = -999;

//    writeBytes((const char*)&pos, sizeof(pos));
488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532
}

/**
 * Sets a random position with an offset of max 1/1000 degree
 * and max 100 m altitude
 */
void QGCXPlaneLink::setRandomPosition()
{
    // Initialize generator
    srand(0);

    double offLat = rand() / static_cast<double>(RAND_MAX) / 500.0 + 1.0/500.0;
    double offLon = rand() / static_cast<double>(RAND_MAX) / 500.0 + 1.0/500.0;
    double offAlt = rand() / static_cast<double>(RAND_MAX) * 200.0 + 100.0;

    if (mav->getAltitude() + offAlt < 0)
    {
        offAlt *= -1.0;
    }

    setPositionAttitude(mav->getLatitude() + offLat,
                        mav->getLongitude() + offLon,
                        mav->getAltitude() + offAlt,
                        mav->getRoll(),
                        mav->getPitch(),
                        mav->getYaw());
}

void QGCXPlaneLink::setRandomAttitude()
{
    // Initialize generator
    srand(0);

    double roll = rand() / static_cast<double>(RAND_MAX) * 2.0 - 1.0;
    double pitch = rand() / static_cast<double>(RAND_MAX) * 2.0 - 1.0;
    double yaw = rand() / static_cast<double>(RAND_MAX) * 2.0 - 1.0;

    setPositionAttitude(mav->getLatitude(),
                        mav->getLongitude(),
                        mav->getAltitude(),
                        roll,
                        pitch,
                        yaw);
}

533 534 535 536 537 538 539 540
/**
 * @brief Connect the connection.
 *
 * @return True if connection has been established, false if connection couldn't be established.
 **/
bool QGCXPlaneLink::connectSimulation()
{
    if (!mav) return false;
541 542
    if (connectState) return false;

543
    socket = new QUdpSocket(this);
544
    connectState = socket->bind(localHost, localPort);
545
    if (!connectState) return false;
546 547 548 549 550 551 552 553 554

    QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes()));

    //process = new QProcess(this);
    //terraSync = new QProcess(this);

    connect(mav, SIGNAL(hilControlsChanged(uint64_t, float, float, float, float, uint8_t, uint8_t)), this, SLOT(updateControls(uint64_t,float,float,float,float,uint8_t,uint8_t)));
    connect(this, SIGNAL(hilStateChanged(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)), mav, SLOT(sendHilState(uint64_t,float,float,float,float,float,float,int32_t,int32_t,int32_t,int16_t,int16_t,int16_t,int16_t,int16_t,int16_t)));

555 556 557 558 559
    UAS* uas = dynamic_cast<UAS*>(mav);
    if (uas)
    {
        uas->startHil();
    }
560

561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602
#pragma pack(push, 1)
    struct iset_struct
    {
        char b[5];
        int index; // (0->20 in the lsit below)
        char str_ipad_them[16];
        char str_port_them[6];
        char padding[2];
        int use_ip;
    } ip; // to use this option, 0 not to.
#pragma pack(pop)

    ip.b[0] = 'I';
    ip.b[1] = 'S';
    ip.b[2] = 'E';
    ip.b[3] = 'T';
    ip.b[4] = '0';

    QList<QHostAddress> hostAddresses = QNetworkInterface::allAddresses();

    QString localAddrStr;
    QString localPortStr = QString("%1").arg(localPort);

    for (int i = 0; i < hostAddresses.size(); i++)
    {
        // Exclude loopback IPv4 and all IPv6 addresses
        if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":"))
        {
            localAddrStr = hostAddresses.at(i).toString();
            break;
        }
    }

    qDebug() << "REQ SEND TO:" << localAddrStr << localPortStr;

    ip.index = 0;
    strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16));
    strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6));
    ip.use_ip = 1;

    writeBytes((const char*)&ip, sizeof(ip));

603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677
    // XXX This will later be enabled to start X-Plane from within QGroundControl with the right arguments

//    //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate()));
//    // Catch process error
//    QObject::connect( process, SIGNAL(error(QProcess::ProcessError)),
//                      this, SLOT(processError(QProcess::ProcessError)));
//    QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
//                      this, SLOT(processError(QProcess::ProcessError)));
//    // Start X-Plane
//    QStringList processCall;
//    QString processFgfs;
//    QString processTerraSync;
//    QString fgRoot;
//    QString fgScenery;
//    QString aircraft;

//    if (mav->getSystemType() == MAV_TYPE_FIXED_WING)
//    {
//        aircraft = "Rascal110-JSBSim";
//    }
//    else if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        aircraft = "arducopter";
//    }
//    else
//    {
//        aircraft = "Rascal110-JSBSim";
//    }

//#ifdef Q_OS_MACX
//    processFgfs = "/Applications/X-Plane.app/Contents/Resources/fgfs";
//    processTerraSync = "/Applications/X-Plane.app/Contents/Resources/terrasync";
//    fgRoot = "/Applications/X-Plane.app/Contents/Resources/data";
//    //fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery";
//    fgScenery = "/Applications/X-Plane.app/Contents/Resources/data/Scenery-TerraSync";
//    //   /Applications/X-Plane.app/Contents/Resources/data/Scenery:
//#endif

//#ifdef Q_OS_WIN32
//    processFgfs = "C:\\Program Files (x86)\\X-Plane\\bin\\Win32\\fgfs";
//    fgRoot = "C:\\Program Files (x86)\\X-Plane\\data";
//    fgScenery = "C:\\Program Files (x86)\\X-Plane\\data\\Scenery-Terrasync";
//#endif

//#ifdef Q_OS_LINUX
//    processFgfs = "fgfs";
//    fgRoot = "/usr/share/X-Plane/data";
//    fgScenery = "/usr/share/X-Plane/data/Scenery-Terrasync";
//#endif

//    // Sanity checks
//    bool sane = true;
//    QFileInfo executable(processFgfs);
//    if (!executable.isExecutable())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane was not found at %1").arg(processFgfs));
//        sane = false;
//    }

//    QFileInfo root(fgRoot);
//    if (!root.isDir())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane data directory was not found at %1").arg(fgRoot));
//        sane = false;
//    }

//    QFileInfo scenery(fgScenery);
//    if (!scenery.isDir())
//    {
//        MainWindow::instance()->showCriticalMessage(tr("X-Plane Failed to Start"), tr("X-Plane scenery directory was not found at %1").arg(fgScenery));
//        sane = false;
//    }

//    if (!sane) return false;

678
//    // --atlas=socket,out,1,locallocalHost,5505,udp
679 680 681 682 683 684 685
//    // terrasync -p 5505 -S -d /usr/local/share/TerraSync

//    processCall << QString("--fg-root=%1").arg(fgRoot);
//    processCall << QString("--fg-scenery=%1").arg(fgScenery);
//    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        // FIXME ADD QUAD-Specific protocol here
686 687
//        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
//        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
688 689 690
//    }
//    else
//    {
691 692
//        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(localPort);
//        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(remotePort);
693
//    }
694
//    processCall << "--atlas=socket,out,1,locallocalHost,5505,udp";
695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760
//    processCall << "--in-air";
//    processCall << "--roll=0";
//    processCall << "--pitch=0";
//    processCall << "--vc=90";
//    processCall << "--heading=300";
//    processCall << "--timeofday=noon";
//    processCall << "--disable-hud-3d";
//    processCall << "--disable-fullscreen";
//    processCall << "--geometry=400x300";
//    processCall << "--disable-anti-alias-hud";
//    processCall << "--wind=0@0";
//    processCall << "--turbulence=0.0";
//    processCall << "--prop:/sim/frame-rate-throttle-hz=30";
//    processCall << "--control=mouse";
//    processCall << "--disable-intro-music";
//    processCall << "--disable-sound";
//    processCall << "--disable-random-objects";
//    processCall << "--disable-ai-models";
//    processCall << "--shading-flat";
//    processCall << "--fog-disable";
//    processCall << "--disable-specular-highlight";
//    //processCall << "--disable-skyblend";
//    processCall << "--disable-random-objects";
//    processCall << "--disable-panel";
//    //processCall << "--disable-horizon-effect";
//    processCall << "--disable-clouds";
//    processCall << "--fdm=jsb";
//    processCall << "--units-meters";
//    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
//    {
//        // Start all engines of the quad
//        processCall << "--prop:/engines/engine[0]/running=true";
//        processCall << "--prop:/engines/engine[1]/running=true";
//        processCall << "--prop:/engines/engine[2]/running=true";
//        processCall << "--prop:/engines/engine[3]/running=true";
//    }
//    else
//    {
//        processCall << "--prop:/engines/engine/running=true";
//    }
//    processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
//    processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
//    processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
//    // Add new argument with this: processCall << "";
//    processCall << QString("--aircraft=%2").arg(aircraft);


//    QStringList terraSyncArguments;
//    terraSyncArguments << "-p 5505";
//    terraSyncArguments << "-S";
//    terraSyncArguments << QString("-d=%1").arg(fgScenery);

//    terraSync->start(processTerraSync, terraSyncArguments);
//    process->start(processFgfs, processCall);



//    emit X-PlaneConnected(connectState);
//    if (connectState) {
//        emit X-PlaneConnected();
//        connectionStartTime = QGC::groundTimeUsecs()/1000;
//    }
//    qDebug() << "STARTING SIM";

//        qDebug() << "STARTING: " << processFgfs << processCall;

761
    qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort;
762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786

    start(LowPriority);
    return connectState;
}

/**
 * @brief Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
bool QGCXPlaneLink::isConnected()
{
    return connectState;
}

QString QGCXPlaneLink::getName()
{
    return name;
}

void QGCXPlaneLink::setName(QString name)
{
    this->name = name;
    //    emit nameChanged(this->name);
}