QGCFlightGearLink.cc 16.9 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

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

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

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

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

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

106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
/**
 * @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
131
            currentPort = host.split(":").last().toInt();
132 133 134 135 136 137 138 139 140 141 142
        }
    }
    else
    {
        QHostInfo info = QHostInfo::fromName(host);
        if (info.error() == QHostInfo::NoError)
        {
            // Add host
            currentHost = info.addresses().first();
        }
    }
143

144 145
}

146 147 148 149 150
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
151
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
152
{
LM's avatar
LM committed
153 154
    // magnetos,aileron,elevator,rudder,throttle\n

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

lm's avatar
lm committed
160 161
    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
162
    writeBytes(state.toAscii().constData(), state.length());
lm's avatar
lm committed
163
    //qDebug() << "Updated controls" << state;
lm's avatar
lm committed
164 165
}

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

/**
 * @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;
201
    char data[maxLength];
202 203 204 205 206 207 208 209
    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
210 211 212

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

lm's avatar
lm committed
215 216 217 218 219 220 221 222 223
    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
224 225

    // Parse string
lm's avatar
lm committed
226
    double time;
lm's avatar
lm committed
227
    float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
lm's avatar
lm committed
228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251
    double lat, lon, alt;
    double vx, vy, vz, xacc, yacc, zacc;
    double airspeed;

    time = values.at(0).toDouble();
    lat = values.at(1).toDouble();
    lon = values.at(2).toDouble();
    alt = values.at(3).toDouble();
    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();

    vx = values.at(13).toDouble();
    vy = values.at(14).toDouble();
    vz = values.at(15).toDouble();

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

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


/**
 * @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
285
bool QGCFlightGearLink::disconnectSimulation()
286
{
LM's avatar
LM committed
287
    disconnect(process, SIGNAL(error(QProcess::ProcessError)),
288
               this, SLOT(processError(QProcess::ProcessError)));
LM's avatar
LM committed
289 290 291
    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
292 293 294 295 296 297
    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
lm's avatar
lm committed
298 299 300 301 302 303
    if (terraSync)
    {
        terraSync->close();
        delete terraSync;
        terraSync = NULL;
    }
LM's avatar
LM committed
304 305
    if (socket)
    {
lm's avatar
lm committed
306
        socket->close();
LM's avatar
LM committed
307 308 309
        delete socket;
        socket = NULL;
    }
310 311 312

    connectState = false;

313 314
    emit simulationDisconnected();
    emit simulationConnected(false);
315 316 317 318 319 320 321 322
    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
323
bool QGCFlightGearLink::connectSimulation()
324
{
lm's avatar
lm committed
325
    if (!mav) return false;
326 327 328 329 330
    socket = new QUdpSocket(this);
    connectState = socket->bind(host, port);

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

lm's avatar
lm committed
331
    process = new QProcess(this);
lm's avatar
lm committed
332
    terraSync = new QProcess(this);
lm's avatar
lm committed
333

lm's avatar
lm committed
334 335
    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)));
336

lm's avatar
lm committed
337 338 339 340
    //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
341 342
    QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
                      this, SLOT(processError(QProcess::ProcessError)));
343 344 345
    // Start Flightgear
    QStringList processCall;
    QString processFgfs;
lm's avatar
lm committed
346
    QString processTerraSync;
347 348
    QString fgRoot;
    QString fgScenery;
lm's avatar
lm committed
349 350 351 352 353 354 355 356 357 358 359 360 361 362
    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";
    }
lm's avatar
lm committed
363 364

#ifdef Q_OS_MACX
365
    processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs";
lm's avatar
lm committed
366 367 368 369 370
    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
371 372 373
#endif

#ifdef Q_OS_WIN32
374
    processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs";
lm's avatar
lm committed
375 376
    fgRoot = "C:\\Program Files (x86)\\FlightGear\\data";
    fgScenery = "C:\\Program Files (x86)\\FlightGear\\data\\Scenery-Terrasync";
lm's avatar
lm committed
377 378
#endif

LM's avatar
LM committed
379
#ifdef Q_OS_LINUX
380
    processFgfs = "fgfs";
lm's avatar
lm committed
381 382
    fgRoot = "/usr/share/flightgear/data";
    fgScenery = "/usr/share/flightgear/data/Scenery-Terrasync";
LM's avatar
LM committed
383 384
#endif

lm's avatar
lm committed
385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426
    // 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;
    }

    if (!sane) return false;

    // --atlas=socket,out,1,localhost,5505,udp
    // 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
        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(port);
        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(currentPort);
    }
    else
    {
        processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(port);
        processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(currentPort);
    }
    processCall << "--atlas=socket,out,1,localhost,5505,udp";
427
    processCall << "--in-air";
lm's avatar
lm committed
428 429
    processCall << "--roll=0";
    processCall << "--pitch=0";
430 431 432 433 434
    processCall << "--vc=90";
    processCall << "--heading=300";
    processCall << "--timeofday=noon";
    processCall << "--disable-hud-3d";
    processCall << "--disable-fullscreen";
lm's avatar
lm committed
435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452
    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";
453
    processCall << "--fdm=jsb";
lm's avatar
lm committed
454
    processCall << "--units-meters";
455 456
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
lm's avatar
lm committed
457 458
        // Start all engines of the quad
        processCall << "--prop:/engines/engine[0]/running=true";
459 460 461 462
        processCall << "--prop:/engines/engine[1]/running=true";
        processCall << "--prop:/engines/engine[2]/running=true";
        processCall << "--prop:/engines/engine[3]/running=true";
    }
lm's avatar
lm committed
463 464 465 466
    else
    {
        processCall << "--prop:/engines/engine/running=true";
    }
467 468 469
    processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
    processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
    processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
470 471
    // Add new argument with this: processCall << "";
    processCall << QString("--aircraft=%2").arg(aircraft);
lm's avatar
lm committed
472

lm's avatar
lm committed
473 474 475 476 477 478 479

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

    terraSync->start(processTerraSync, terraSyncArguments);
lm's avatar
lm committed
480
    process->start(processFgfs, processCall);
lm's avatar
lm committed
481 482


LM's avatar
LM committed
483

484
    emit simulationConnected(connectState);
lm's avatar
lm committed
485
    if (connectState) {
486
        emit simulationConnected();
lm's avatar
lm committed
487 488 489
        connectionStartTime = QGC::groundTimeUsecs()/1000;
    }
    qDebug() << "STARTING SIM";
LM's avatar
LM committed
490 491

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

lm's avatar
lm committed
493
    start(LowPriority);
494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511
    return connectState;
}

/**
 * @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
512 513 514 515 516
QString QGCFlightGearLink::getRemoteHost()
{
    return QString("%1:%2").arg(currentHost.toString(), currentPort);
}

517 518 519
void QGCFlightGearLink::setName(QString name)
{
    this->name = name;
lm's avatar
lm committed
520
    //    emit nameChanged(this->name);
521
}