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

QGCFlightGearLink::~QGCFlightGearLink()
{
LM's avatar
LM committed
57
    disconnectSimulation();
58 59 60 61 62 63 64 65 66 67 68 69 70 71
}

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

void QGCFlightGearLink::setPort(int port)
{
    this->port = port;
lm's avatar
lm committed
72 73
    disconnectSimulation();
    connectSimulation();
74 75
}

lm's avatar
lm committed
76 77 78 79 80 81 82 83 84 85 86
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:
87
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
88 89
        break;
    case QProcess::WriteError:
90
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
91 92
        break;
    case QProcess::ReadError:
93
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
94 95 96 97 98 99 100 101
        break;
    case QProcess::UnknownError:
    default:
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct."));
        break;
    }
}

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

lm's avatar
lm committed
141
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
142
{
LM's avatar
LM committed
143 144
    // magnetos,aileron,elevator,rudder,throttle\n

lm's avatar
lm committed
145
    //float magnetos = 3.0f;
lm's avatar
lm committed
146 147 148
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);
LM's avatar
LM committed
149

lm's avatar
lm committed
150 151
    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
152
    writeBytes(state.toAscii().constData(), state.length());
lm's avatar
lm committed
153
    //qDebug() << "Updated controls" << state;
lm's avatar
lm committed
154 155
}

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

/**
 * @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;
    static 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);
lm's avatar
lm committed
200 201 202

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

lm's avatar
lm committed
205 206 207 208 209 210 211 212 213
    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
214 215

    // Parse string
lm's avatar
lm committed
216
    double time;
lm's avatar
lm committed
217
    float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
lm's avatar
lm committed
218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241
    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
242 243 244 245 246 247 248 249 250 251 252 253 254 255 256

    // 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;
257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274
}


/**
 * @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
275
bool QGCFlightGearLink::disconnectSimulation()
276
{
LM's avatar
LM committed
277
    disconnect(process, SIGNAL(error(QProcess::ProcessError)),
278
               this, SLOT(processError(QProcess::ProcessError)));
LM's avatar
LM committed
279 280 281
    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
282 283 284 285 286 287
    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
lm's avatar
lm committed
288 289 290 291 292 293
    if (terraSync)
    {
        terraSync->close();
        delete terraSync;
        terraSync = NULL;
    }
LM's avatar
LM committed
294 295
    if (socket)
    {
lm's avatar
lm committed
296
        socket->close();
LM's avatar
LM committed
297 298 299
        delete socket;
        socket = NULL;
    }
300 301 302

    connectState = false;

lm's avatar
lm committed
303 304
    emit flightGearDisconnected();
    emit flightGearConnected(false);
305 306 307 308 309 310 311 312
    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
313
bool QGCFlightGearLink::connectSimulation()
314
{
lm's avatar
lm committed
315
    if (!mav) return false;
316 317 318 319 320
    socket = new QUdpSocket(this);
    connectState = socket->bind(host, port);

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

lm's avatar
lm committed
321
    process = new QProcess(this);
lm's avatar
lm committed
322
    terraSync = new QProcess(this);
lm's avatar
lm committed
323

lm's avatar
lm committed
324 325
    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)));
326

lm's avatar
lm committed
327 328 329 330
    //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
331 332
    QObject::connect( terraSync, SIGNAL(error(QProcess::ProcessError)),
                      this, SLOT(processError(QProcess::ProcessError)));
333 334 335
    // Start Flightgear
    QStringList processCall;
    QString processFgfs;
lm's avatar
lm committed
336
    QString processTerraSync;
337 338
    QString fgRoot;
    QString fgScenery;
lm's avatar
lm committed
339 340 341 342 343 344 345 346 347 348 349 350 351 352
    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
353 354

#ifdef Q_OS_MACX
355
    processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs";
lm's avatar
lm committed
356 357 358 359 360
    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
361 362 363
#endif

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

LM's avatar
LM committed
369
#ifdef Q_OS_LINUX
370
    processFgfs = "fgfs";
lm's avatar
lm committed
371 372
    fgRoot = "/usr/share/flightgear/data";
    fgScenery = "/usr/share/flightgear/data/Scenery-Terrasync";
LM's avatar
LM committed
373 374
#endif

lm's avatar
lm committed
375 376 377 378 379 380 381 382 383 384 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
    // 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";
417
    processCall << "--in-air";
lm's avatar
lm committed
418 419
    processCall << "--roll=0";
    processCall << "--pitch=0";
420 421 422 423 424
    processCall << "--vc=90";
    processCall << "--heading=300";
    processCall << "--timeofday=noon";
    processCall << "--disable-hud-3d";
    processCall << "--disable-fullscreen";
lm's avatar
lm committed
425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442
    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";
443
    processCall << "--fdm=jsb";
lm's avatar
lm committed
444
    processCall << "--units-meters";
445 446
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
lm's avatar
lm committed
447 448
        // Start all engines of the quad
        processCall << "--prop:/engines/engine[0]/running=true";
449 450 451 452
        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
453 454 455 456
    else
    {
        processCall << "--prop:/engines/engine/running=true";
    }
457 458 459
    processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
    processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
    processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
460 461
    // Add new argument with this: processCall << "";
    processCall << QString("--aircraft=%2").arg(aircraft);
lm's avatar
lm committed
462

lm's avatar
lm committed
463 464 465 466 467 468 469

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

    terraSync->start(processTerraSync, terraSyncArguments);
lm's avatar
lm committed
470
    process->start(processFgfs, processCall);
lm's avatar
lm committed
471 472


LM's avatar
LM committed
473

lm's avatar
lm committed
474 475 476 477 478 479
    emit flightGearConnected(connectState);
    if (connectState) {
        emit flightGearConnected();
        connectionStartTime = QGC::groundTimeUsecs()/1000;
    }
    qDebug() << "STARTING SIM";
LM's avatar
LM committed
480 481

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

lm's avatar
lm committed
483
    start(LowPriority);
484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504
    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;
}

void QGCFlightGearLink::setName(QString name)
{
    this->name = name;
lm's avatar
lm committed
505
    //    emit nameChanged(this->name);
506
}