QGCFlightGearLink.cc 19.6 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
/*=====================================================================

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
 *   @brief Definition of UDP connection (server) for unmanned vehicles
lm's avatar
lm committed
27
 *   @see Flightgear Manual http://mapserver.flightgear.org/getstart.pdf
28 29 30 31 32 33 34 35 36 37 38 39
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QTimer>
#include <QList>
#include <QDebug>
#include <QMutexLocker>
#include <iostream>
#include "QGCFlightGearLink.h"
#include "QGC.h"
#include <QHostInfo>
lm's avatar
lm committed
40
#include "MainWindow.h"
41

42
QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) :
lm's avatar
lm committed
43
    process(NULL),
Lorenz Meier's avatar
Lorenz Meier committed
44
    terraSync(NULL),
Lorenz Meier's avatar
Lorenz Meier committed
45
    socket(NULL),
46
    startupArguments(startupArguments),
Lorenz Meier's avatar
Lorenz Meier committed
47
    flightGearVersion(0)
48 49
{
    this->host = host;
50
    this->port = port+mav->getUASID();
51
    this->connectState = false;
52
    this->currentPort = 49000+mav->getUASID();
lm's avatar
lm committed
53
    this->mav = mav;
lm's avatar
lm committed
54
    this->name = tr("FlightGear Link (port:%1)").arg(port);
LM's avatar
LM committed
55
    setRemoteHost(remoteHost);
56 57 58
}

QGCFlightGearLink::~QGCFlightGearLink()
59 60
{   //do not disconnect unless it is connected.
    //disconnectSimulation will delete the memory that was allocated for proces, terraSync and socket
61 62 63
    if(connectState){
       disconnectSimulation();
    }
64 65 66 67 68 69 70 71 72 73 74 75 76 77
}

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

void QGCFlightGearLink::setPort(int port)
{
    this->port = port;
lm's avatar
lm committed
78 79
    disconnectSimulation();
    connectSimulation();
80 81
}

lm's avatar
lm committed
82 83 84 85 86
void QGCFlightGearLink::processError(QProcess::ProcessError err)
{
    switch(err)
    {
    case QProcess::FailedToStart:
87
        MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Failed to Start"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
88 89
        break;
    case QProcess::Crashed:
90
        MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear"));
lm's avatar
lm committed
91 92
        break;
    case QProcess::Timedout:
93
        MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Start Timed Out"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
94 95
        break;
    case QProcess::WriteError:
96
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear/TerraSync"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
97 98
        break;
    case QProcess::ReadError:
99
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear/TerraSync"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
100 101 102
        break;
    case QProcess::UnknownError:
    default:
103
        MainWindow::instance()->showCriticalMessage(tr("FlightGear/TerraSync Error"), tr("Please check if the path and command is correct."));
lm's avatar
lm committed
104 105 106 107
        break;
    }
}

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

146 147
}

148 149 150 151 152
void QGCFlightGearLink::updateActuators(uint64_t time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
{

}

lm's avatar
lm committed
153
void QGCFlightGearLink::updateControls(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode)
lm's avatar
lm committed
154
{
LM's avatar
LM committed
155 156
    // magnetos,aileron,elevator,rudder,throttle\n

lm's avatar
lm committed
157
    //float magnetos = 3.0f;
lm's avatar
lm committed
158 159 160
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);
LM's avatar
LM committed
161

lm's avatar
lm committed
162 163
    QString state("%1\t%2\t%3\t%4\t%5\n");
    state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle);
lm's avatar
lm committed
164
    writeBytes(state.toAscii().constData(), state.length());
lm's avatar
lm committed
165
    //qDebug() << "Updated controls" << state;
lm's avatar
lm committed
166 167
}

168 169
void QGCFlightGearLink::writeBytes(const char* data, qint64 size)
{
lm's avatar
lm committed
170
    //#define QGCFlightGearLink_DEBUG
171
#ifdef QGCFlightGearLink_DEBUG
lm's avatar
lm committed
172 173 174 175 176 177 178
    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)
179
        {
lm's avatar
lm committed
180
            ascii.append(data[i]);
181
        }
lm's avatar
lm committed
182 183 184 185 186 187 188 189
        else
        {
            ascii.append(219);
        }
    }
    qDebug() << "Sent" << size << "bytes to" << currentHost.toString() << ":" << currentPort << "data:";
    qDebug() << bytes;
    qDebug() << "ASCII:" << ascii;
190
#endif
LM's avatar
LM committed
191
    if (connectState && socket) socket->writeDatagram(data, size, currentHost, currentPort);
192 193 194 195 196 197 198 199 200 201 202
}

/**
 * @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 QGCFlightGearLink::readBytes()
{
    const qint64 maxLength = 65536;
203
    char data[maxLength];
204 205 206 207 208 209 210 211
    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);
lm's avatar
lm committed
212 213 214

    // Print string
    QString state(b);
LM's avatar
LM committed
215
    //qDebug() << "FG LINK GOT:" << state;
lm's avatar
lm committed
216

lm's avatar
lm committed
217 218 219 220 221 222 223 224 225
    QStringList values = state.split("\t");

    // Check length
    if (values.size() != 17)
    {
        qDebug() << "RETURN LENGTH MISMATCHING EXPECTED" << 17 << "BUT GOT" << values.size();
        qDebug() << state;
        return;
    }
lm's avatar
lm committed
226 227

    // Parse string
lm's avatar
lm committed
228
    double time;
lm's avatar
lm committed
229
    float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
lm's avatar
lm committed
230 231 232 233 234
    double lat, lon, alt;
    double vx, vy, vz, xacc, yacc, zacc;
    double airspeed;

    time = values.at(0).toDouble();
235 236 237
    lat = values.at(1).toDouble() * 1e7;
    lon = values.at(2).toDouble() * 1e7;
    alt = values.at(3).toDouble() * 1e3;
lm's avatar
lm committed
238 239 240 241 242 243 244 245 246 247 248
    roll = values.at(4).toDouble();
    pitch = values.at(5).toDouble();
    yaw = values.at(6).toDouble();
    rollspeed = values.at(7).toDouble();
    pitchspeed = values.at(8).toDouble();
    yawspeed = values.at(9).toDouble();

    xacc = values.at(10).toDouble();
    yacc = values.at(11).toDouble();
    zacc = values.at(12).toDouble();

249 250 251
    vx = values.at(13).toDouble() * 1e2;
    vy = values.at(14).toDouble() * 1e2;
    vz = values.at(15).toDouble() * 1e2;
lm's avatar
lm committed
252 253

    airspeed = values.at(16).toDouble();
lm's avatar
lm committed
254 255 256 257 258 259 260 261 262 263 264 265 266 267 268

    // Send updated state
    emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
                         pitchspeed, yawspeed, lat, lon, alt,
                         vx, vy, vz, xacc, yacc, zacc);

    //    // 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;
269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286
}


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

/**
 * @brief Disconnect the connection.
 *
 * @return True if connection has been disconnected, false if connection couldn't be disconnected.
 **/
lm's avatar
lm committed
287
bool QGCFlightGearLink::disconnectSimulation()
288
{
LM's avatar
LM committed
289
    disconnect(process, SIGNAL(error(QProcess::ProcessError)),
290
               this, SLOT(processError(QProcess::ProcessError)));
LM's avatar
LM committed
291 292 293
    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)));

LM's avatar
LM committed
294 295 296 297 298 299
    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
lm's avatar
lm committed
300 301 302 303 304 305
    if (terraSync)
    {
        terraSync->close();
        delete terraSync;
        terraSync = NULL;
    }
LM's avatar
LM committed
306 307
    if (socket)
    {
lm's avatar
lm committed
308
        socket->close();
LM's avatar
LM committed
309 310 311
        delete socket;
        socket = NULL;
    }
312 313 314

    connectState = false;

315 316
    emit simulationDisconnected();
    emit simulationConnected(false);
317 318 319 320 321 322 323 324
    return !connectState;
}

/**
 * @brief Connect the connection.
 *
 * @return True if connection has been established, false if connection couldn't be established.
 **/
lm's avatar
lm committed
325
bool QGCFlightGearLink::connectSimulation()
326
{
327 328
    qDebug() << "STARTING FLIGHTGEAR LINK";

lm's avatar
lm committed
329
    if (!mav) return false;
330 331 332 333 334
    socket = new QUdpSocket(this);
    connectState = socket->bind(host, port);

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

lm's avatar
lm committed
335
    process = new QProcess(this);
lm's avatar
lm committed
336
    terraSync = new QProcess(this);
lm's avatar
lm committed
337

lm's avatar
lm committed
338 339
    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)));
340

341 342
    mav->startHil();

lm's avatar
lm committed
343 344 345 346
    //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate()));
    // Catch process error
    QObject::connect( process, SIGNAL(error(QProcess::ProcessError)),
                      this, SLOT(processError(QProcess::ProcessError)));
lm's avatar
lm committed
347 348
    QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
                      this, SLOT(processError(QProcess::ProcessError)));
349
    // Start Flightgear
350
    QStringList flightGearArguments;
351
    QString processFgfs;
lm's avatar
lm committed
352
    QString processTerraSync;
353 354
    QString fgRoot;
    QString fgScenery;
355
    QString terraSyncScenery;
356
    QString fgAircraft;
lm's avatar
lm committed
357 358

#ifdef Q_OS_MACX
359
    processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs";
lm's avatar
lm committed
360 361 362 363 364
    processTerraSync = "/Applications/FlightGear.app/Contents/Resources/terrasync";
    fgRoot = "/Applications/FlightGear.app/Contents/Resources/data";
    //fgScenery = "/Applications/FlightGear.app/Contents/Resources/data/Scenery";
    fgScenery = "/Applications/FlightGear.app/Contents/Resources/data/Scenery-TerraSync";
    //   /Applications/FlightGear.app/Contents/Resources/data/Scenery:
lm's avatar
lm committed
365 366 367
#endif

#ifdef Q_OS_WIN32
368
    processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs";
lm's avatar
lm committed
369 370
    fgRoot = "C:\\Program Files (x86)\\FlightGear\\data";
    fgScenery = "C:\\Program Files (x86)\\FlightGear\\data\\Scenery-Terrasync";
lm's avatar
lm committed
371 372
#endif

LM's avatar
LM committed
373
#ifdef Q_OS_LINUX
374 375
    processFgfs = "/usr/games/fgfs";
    fgRoot = "/usr/share/games/flightgear";
376 377 378
    fgScenery = "/usr/share/games/flightgear/Scenery/";
    processTerraSync = "/usr/bin/nice"; //according to http://wiki.flightgear.org/TerraSync, run with lower priority
    terraSyncScenery = QDir::homePath() + "/.terrasync/Scenery"; //according to http://wiki.flightgear.org/TerraSync a separate directory is used
LM's avatar
LM committed
379 380
#endif

381 382
    fgAircraft = QApplication::applicationDirPath() + "/files/flightgear/Aircraft";

lm's avatar
lm committed
383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405
    // Sanity checks
    bool sane = true;
    QFileInfo executable(processFgfs);
    if (!executable.isExecutable())
    {
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("FlightGear was not found at %1").arg(processFgfs));
        sane = false;
    }

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

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

406 407 408 409 410 411 412 413
    QFileInfo terraSyncExecutableInfo(processTerraSync);
    if (!terraSyncExecutableInfo.isExecutable())
    {
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("TerraSync was not found at %1").arg(processTerraSync));
        sane = false;
    }


lm's avatar
lm committed
414 415 416 417 418
    if (!sane) return false;

    // --atlas=socket,out,1,localhost,5505,udp
    // terrasync -p 5505 -S -d /usr/local/share/TerraSync

419 420 421
    /*Prepare FlightGear Arguments */
    flightGearArguments << QString("--fg-root=%1").arg(fgRoot);
    flightGearArguments << QString("--fg-scenery=%1:%2").arg(fgScenery).arg(terraSyncScenery); //according to http://wiki.flightgear.org/TerraSync a separate directory is used
422
    flightGearArguments << QString("--fg-aircraft=%1").arg(fgAircraft);
lm's avatar
lm committed
423 424 425
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
        // FIXME ADD QUAD-Specific protocol here
426 427
        flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(port);
        flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(currentPort);
lm's avatar
lm committed
428 429 430
    }
    else
    {
431 432
        flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(port);
        flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(currentPort);
lm's avatar
lm committed
433
    }
434
    flightGearArguments << "--atlas=socket,out,1,localhost,5505,udp";
435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465
//    flightGearArguments << "--in-air";
//    flightGearArguments << "--roll=0";
//    flightGearArguments << "--pitch=0";
//    flightGearArguments << "--vc=90";
//    flightGearArguments << "--heading=300";
//    flightGearArguments << "--timeofday=noon";
//    flightGearArguments << "--disable-hud-3d";
//    flightGearArguments << "--disable-fullscreen";
//    flightGearArguments << "--geometry=400x300";
//    flightGearArguments << "--disable-anti-alias-hud";
//    flightGearArguments << "--wind=0@0";
//    flightGearArguments << "--turbulence=0.0";
//    flightGearArguments << "--prop:/sim/frame-rate-throttle-hz=30";
//    flightGearArguments << "--control=mouse";
//    flightGearArguments << "--disable-intro-music";
//    flightGearArguments << "--disable-sound";
//    flightGearArguments << "--disable-random-objects";
//    flightGearArguments << "--disable-ai-models";
//    flightGearArguments << "--shading-flat";
//    flightGearArguments << "--fog-disable";
//    flightGearArguments << "--disable-specular-highlight";
//    //flightGearArguments << "--disable-skyblend";
//    flightGearArguments << "--disable-random-objects";
//    flightGearArguments << "--disable-panel";
//    //flightGearArguments << "--disable-horizon-effect";
//    flightGearArguments << "--disable-clouds";
//    flightGearArguments << "--fdm=jsb";
//    flightGearArguments << "--units-meters"; //XXX: check: the protocol xml has already a conversion from feet to m?
//    flightGearArguments << "--notrim";

    flightGearArguments += startupArguments.split(" ");
466 467
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
lm's avatar
lm committed
468
        // Start all engines of the quad
469 470 471 472
        flightGearArguments << "--prop:/engines/engine[0]/running=true";
        flightGearArguments << "--prop:/engines/engine[1]/running=true";
        flightGearArguments << "--prop:/engines/engine[2]/running=true";
        flightGearArguments << "--prop:/engines/engine[3]/running=true";
473
    }
lm's avatar
lm committed
474 475
    else
    {
476
        flightGearArguments << "--prop:/engines/engine/running=true";
lm's avatar
lm committed
477
    }
478 479 480 481
    flightGearArguments << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
    flightGearArguments << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
    flightGearArguments << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
    // Add new argument with this: flightGearArguments << "";
482
    //flightGearArguments << QString("--aircraft=%2").arg(aircraft);
lm's avatar
lm committed
483

484
    /*Prepare TerraSync Arguments */
lm's avatar
lm committed
485
    QStringList terraSyncArguments;
486 487 488 489 490
#ifdef Q_OS_LINUX
    terraSyncArguments << "/usr/games/terrasync";
#endif
    terraSyncArguments << "-p";
    terraSyncArguments << "5505";
lm's avatar
lm committed
491
    terraSyncArguments << "-S";
492 493
    terraSyncArguments << "-d";
    terraSyncArguments << terraSyncScenery; //according to http://wiki.flightgear.org/TerraSync a separate directory is used
lm's avatar
lm committed
494

495 496
//    connect (terraSync, SIGNAL(readyReadStandardOutput()), this, SLOT(printTerraSyncOutput()));
//    connect (terraSync, SIGNAL(readyReadStandardError()), this, SLOT(printTerraSyncError()));
lm's avatar
lm committed
497
    terraSync->start(processTerraSync, terraSyncArguments);
498 499 500
//    qDebug() << "STARTING: " << processTerraSync << terraSyncArguments;

    process->start(processFgfs, flightGearArguments);
lm's avatar
lm committed
501 502


LM's avatar
LM committed
503

504
    emit simulationConnected(connectState);
lm's avatar
lm committed
505
    if (connectState) {
506
        emit simulationConnected();
lm's avatar
lm committed
507 508 509
        connectionStartTime = QGC::groundTimeUsecs()/1000;
    }
    qDebug() << "STARTING SIM";
LM's avatar
LM committed
510

511 512
//    qDebug() << "STARTING: " << processFgfs << flightGearArguments;

513

lm's avatar
lm committed
514
    start(LowPriority);
515 516 517
    return connectState;
}

518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540
void QGCFlightGearLink::printTerraSyncOutput()
{
   qDebug() << "TerraSync stdout:";
   QByteArray byteArray = terraSync->readAllStandardOutput();
   QStringList strLines = QString(byteArray).split("\n");

   foreach (QString line, strLines){
    qDebug() << line;
   }
}

void QGCFlightGearLink::printTerraSyncError()
{
   qDebug() << "TerraSync stderr:";

   QByteArray byteArray = terraSync->readAllStandardError();
   QStringList strLines = QString(byteArray).split("\n");

   foreach (QString line, strLines){
    qDebug() << line;
   }
}

541 542 543 544 545 546 547 548 549
/**
 * @brief Set the startup arguments used to start flightgear
 *
 **/
void QGCFlightGearLink::setStartupArguments(QString startupArguments)
{
    this->startupArguments = startupArguments;
}

550 551 552 553 554 555 556 557 558 559 560 561 562 563 564
/**
 * @brief Check if connection is active.
 *
 * @return True if link is connected, false otherwise.
 **/
bool QGCFlightGearLink::isConnected()
{
    return connectState;
}

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

Lorenz Meier's avatar
Lorenz Meier committed
565 566 567 568 569
QString QGCFlightGearLink::getRemoteHost()
{
    return QString("%1:%2").arg(currentHost.toString(), currentPort);
}

570 571 572
void QGCFlightGearLink::setName(QString name)
{
    this->name = name;
lm's avatar
lm committed
573
    //    emit nameChanged(this->name);
574
}