QGCFlightGearLink.cc 29.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
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
Thomas Gubler's avatar
Thomas Gubler committed
29
 *   @author Thomas Gubler <thomasgubler@student.ethz.ch>
30 31 32 33 34 35 36 37 38 39 40
 *
 */

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

Don Gagne's avatar
Don Gagne committed
43 44 45 46
// FlightGear process start and connection is quite fragile. Uncomment the define below to get higher level of debug output
// for tracking down problems.
#define DEBUG_FLIGHTGEAR_CONNECT

47
QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) :
48
    socket(NULL),
lm's avatar
lm committed
49
    process(NULL),
Don Gagne's avatar
Don Gagne committed
50
    flightGearVersion(3),
Thomas Gubler's avatar
Thomas Gubler committed
51
    startupArguments(startupArguments),
52
    _sensorHilEnabled(true),
53
    barometerOffsetkPa(0.0f)
54
{
55 56 57 58
    // We're doing it wrong - because the Qt folks got the API wrong:
    // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
    moveToThread(this);

59
    this->host = host;
60
    this->port = port+mav->getUASID();
61
    this->connectState = false;
62
    this->currentPort = 49000+mav->getUASID();
lm's avatar
lm committed
63
    this->mav = mav;
Don Gagne's avatar
Don Gagne committed
64
    this->name = tr("FlightGear 3.0+ Link (port:%1)").arg(port);
LM's avatar
LM committed
65
    setRemoteHost(remoteHost);
66 67 68
}

QGCFlightGearLink::~QGCFlightGearLink()
69 70
{   //do not disconnect unless it is connected.
    //disconnectSimulation will delete the memory that was allocated for proces, terraSync and socket
71 72 73
    if(connectState){
       disconnectSimulation();
    }
74 75 76 77 78 79
}

/**
 * @brief Runs the thread
 *
 **/
Don Gagne's avatar
Don Gagne committed
80

81 82
void QGCFlightGearLink::run()
{
83 84 85 86
    qDebug() << "STARTING FLIGHTGEAR LINK";

    if (!mav) return;
    socket = new QUdpSocket(this);
Lorenz Meier's avatar
Lorenz Meier committed
87
    socket->moveToThread(this);
88 89 90 91 92
    connectState = socket->bind(host, port);

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

    process = new QProcess(this);
Lorenz Meier's avatar
Lorenz Meier committed
93
    process->moveToThread(this);
94
    terraSync = new QProcess(this);
Lorenz Meier's avatar
Lorenz Meier committed
95
    terraSync->moveToThread(this);
96

97
    connect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8)));
98 99 100 101 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 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296
    connect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)));
    connect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int)));
    connect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)));

    UAS* uas = dynamic_cast<UAS*>(mav);
    if (uas)
    {
        uas->startHil();
    }

    //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 Flightgear
    QStringList flightGearArguments;
    QString processFgfs;
    QString processTerraSync;
    QString fgRoot;
    QString fgScenery;
    QString terraSyncScenery;
    QString fgAircraft;

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

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

#ifdef Q_OS_LINUX
    processFgfs = "fgfs";
    //fgRoot = "/usr/share/flightgear";
    QString fgScenery1 = "/usr/share/flightgear/data/Scenery";
    QString fgScenery2 = "/usr/share/games/flightgear/Scenery"; // Ubuntu default location
    fgScenery = ""; //Flightgear can also start with fgScenery = ""
    if (QDir(fgScenery1).exists())
        fgScenery = fgScenery1;
    else if (QDir(fgScenery2).exists())
        fgScenery = fgScenery2;


    processTerraSync = "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
#endif

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

    // 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;
//    }

//    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;
//    }


    if (!sane) return;

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

    /*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
    flightGearArguments << QString("--fg-aircraft=%1").arg(fgAircraft);
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
        flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol-quadrotor").arg(port);
        flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol-quadrotor").arg(currentPort);
    }
    else
    {
        flightGearArguments << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol-fixed-wing").arg(port);
        flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol-fixed-wing").arg(currentPort);
    }
    flightGearArguments << "--atlas=socket,out,1,localhost,5505,udp";
//    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(" ");
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
        // Start all engines of the quad
        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";
    }
    else
    {
        flightGearArguments << "--prop:/engines/engine/running=true";
    }
    flightGearArguments << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
    flightGearArguments << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
    //The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear
    //Without the altitude-setting the aircraft is positioned on the ground
    //flightGearArguments << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());

    // Add new argument with this: flightGearArguments << "";
    //flightGearArguments << QString("--aircraft=%2").arg(aircraft);

    /*Prepare TerraSync Arguments */
    QStringList terraSyncArguments;
#ifdef Q_OS_LINUX
    terraSyncArguments << "terrasync";
#endif
    terraSyncArguments << "-p";
    terraSyncArguments << "5505";
    terraSyncArguments << "-S";
    terraSyncArguments << "-d";
    terraSyncArguments << terraSyncScenery; //according to http://wiki.flightgear.org/TerraSync a separate directory is used

#ifdef Q_OS_LINUX
     /* Setting environment */
    QProcessEnvironment env = QProcessEnvironment::systemEnvironment();
    process->setProcessEnvironment(env);
    terraSync->setProcessEnvironment(env);
#endif
//    connect (terraSync, SIGNAL(readyReadStandardOutput()), this, SLOT(printTerraSyncOutput()));
//    connect (terraSync, SIGNAL(readyReadStandardError()), this, SLOT(printTerraSyncError()));
    terraSync->start(processTerraSync, terraSyncArguments);
//    qDebug() << "STARTING: " << processTerraSync << terraSyncArguments;

    process->start(processFgfs, flightGearArguments);
//    connect (process, SIGNAL(readyReadStandardOutput()), this, SLOT(printFgfsOutput()));
//    connect (process, SIGNAL(readyReadStandardError()), this, SLOT(printFgfsError()));



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

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

297 298 299 300 301 302
    exec();
}

void QGCFlightGearLink::setPort(int port)
{
    this->port = port;
lm's avatar
lm committed
303 304
    disconnectSimulation();
    connectSimulation();
305 306
}

lm's avatar
lm committed
307 308 309 310 311
void QGCFlightGearLink::processError(QProcess::ProcessError err)
{
    switch(err)
    {
    case QProcess::FailedToStart:
Don Gagne's avatar
Don Gagne committed
312
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
313 314
        break;
    case QProcess::Crashed:
Don Gagne's avatar
Don Gagne committed
315
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear"));
lm's avatar
lm committed
316 317
        break;
    case QProcess::Timedout:
Don Gagne's avatar
Don Gagne committed
318
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
319 320
        break;
    case QProcess::WriteError:
Don Gagne's avatar
Don Gagne committed
321
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
322 323
        break;
    case QProcess::ReadError:
Don Gagne's avatar
Don Gagne committed
324
        MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
lm's avatar
lm committed
325 326 327
        break;
    case QProcess::UnknownError:
    default:
Don Gagne's avatar
Don Gagne committed
328
        MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct."));
lm's avatar
lm committed
329 330 331 332
        break;
    }
}

333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357
/**
 * @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
358
            currentPort = host.split(":").last().toInt();
359 360 361 362 363 364 365 366 367 368 369
        }
    }
    else
    {
        QHostInfo info = QHostInfo::fromName(host);
        if (info.error() == QHostInfo::NoError)
        {
            // Add host
            currentHost = info.addresses().first();
        }
    }
370

371 372
}

373
void QGCFlightGearLink::updateActuators(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8)
374
{
375 376 377 378 379 380 381 382 383
    Q_UNUSED(time);
    Q_UNUSED(act1);
    Q_UNUSED(act2);
    Q_UNUSED(act3);
    Q_UNUSED(act4);
    Q_UNUSED(act5);
    Q_UNUSED(act6);
    Q_UNUSED(act7);
    Q_UNUSED(act8);
384 385
}

386
void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode)
lm's avatar
lm committed
387
{
LM's avatar
LM committed
388 389
    // magnetos,aileron,elevator,rudder,throttle\n

lm's avatar
lm committed
390
    //float magnetos = 3.0f;
lm's avatar
lm committed
391 392 393
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);
LM's avatar
LM committed
394

395 396 397 398 399
    if(!isnan(rollAilerons) && !isnan(pitchElevator) && !isnan(yawRudder) && !isnan(throttle))
    {
        QString state("%1\t%2\t%3\t%4\t%5\n");
        state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle);
        writeBytes(state.toAscii().constData(), state.length());
Thomas Gubler's avatar
Thomas Gubler committed
400
//        qDebug() << "updated controls" << rollAilerons << pitchElevator << yawRudder << throttle;
401 402 403 404 405
    }
    else
    {
        qDebug() << "HIL: Got NaN values from the hardware: isnan output: roll: " << isnan(rollAilerons) << ", pitch: " << isnan(pitchElevator) << ", yaw: " << isnan(yawRudder) << ", throttle: " << isnan(throttle);
    }
lm's avatar
lm committed
406
    //qDebug() << "Updated controls" << state;
lm's avatar
lm committed
407 408
}

409 410
void QGCFlightGearLink::writeBytes(const char* data, qint64 size)
{
lm's avatar
lm committed
411
    //#define QGCFlightGearLink_DEBUG
412
#ifdef QGCFlightGearLink_DEBUG
lm's avatar
lm committed
413 414 415 416 417 418 419
    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)
420
        {
lm's avatar
lm committed
421
            ascii.append(data[i]);
422
        }
lm's avatar
lm committed
423 424 425 426 427 428 429 430
        else
        {
            ascii.append(219);
        }
    }
    qDebug() << "Sent" << size << "bytes to" << currentHost.toString() << ":" << currentPort << "data:";
    qDebug() << bytes;
    qDebug() << "ASCII:" << ascii;
431
#endif
LM's avatar
LM committed
432
    if (connectState && socket) socket->writeDatagram(data, size, currentHost, currentPort);
433 434 435 436 437 438 439 440 441 442 443
}

/**
 * @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;
444
    char data[maxLength];
445 446 447 448 449 450 451 452
    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
453 454 455

    // Print string
    QString state(b);
Thomas Gubler's avatar
Thomas Gubler committed
456
//    qDebug() << "FG LINK GOT:" << state;
lm's avatar
lm committed
457

lm's avatar
lm committed
458 459 460
    QStringList values = state.split("\t");

    // Check length
461 462
    const int nValues = 21;
    if (values.size() != nValues)
lm's avatar
lm committed
463
    {
464
        qDebug() << "RETURN LENGTH MISMATCHING EXPECTED" << nValues << "BUT GOT" << values.size();
lm's avatar
lm committed
465 466 467
        qDebug() << state;
        return;
    }
lm's avatar
lm committed
468 469 470

    // Parse string
    float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
Thomas Gubler's avatar
Thomas Gubler committed
471 472 473 474 475 476 477 478
    double lat, lon, alt;   
    float ind_airspeed;
    float true_airspeed;
    float vx, vy, vz, xacc, yacc, zacc;
    float diff_pressure;
    float temperature;
    float abs_pressure;
    float mag_variation, mag_dip, xmag_ned, ymag_ned, zmag_ned, xmag_body, ymag_body, zmag_body;
479

lm's avatar
lm committed
480

Lorenz Meier's avatar
Lorenz Meier committed
481 482 483
    lat = values.at(1).toDouble();
    lon = values.at(2).toDouble();
    alt = values.at(3).toDouble();
Thomas Gubler's avatar
Thomas Gubler committed
484 485 486 487 488 489
    roll = values.at(4).toFloat();
    pitch = values.at(5).toFloat();
    yaw = values.at(6).toFloat();
    rollspeed = values.at(7).toFloat();
    pitchspeed = values.at(8).toFloat();
    yawspeed = values.at(9).toFloat();
lm's avatar
lm committed
490

Thomas Gubler's avatar
Thomas Gubler committed
491 492 493
    xacc = values.at(10).toFloat();
    yacc = values.at(11).toFloat();
    zacc = values.at(12).toFloat();
lm's avatar
lm committed
494

Thomas Gubler's avatar
Thomas Gubler committed
495 496 497 498 499 500
    vx = values.at(13).toFloat();
    vy = values.at(14).toFloat();
    vz = values.at(15).toFloat();

    true_airspeed = values.at(16).toFloat();

501 502
    mag_variation = values.at(17).toFloat();
    mag_dip = values.at(18).toFloat();
Thomas Gubler's avatar
Thomas Gubler committed
503

504
    temperature = values.at(19).toFloat();
505 506
    abs_pressure = values.at(20).toFloat() * 1e2f; //convert to Pa from hPa
    abs_pressure += barometerOffsetkPa * 1e3f; //add offset, convert from kPa to Pa
lm's avatar
lm committed
507

508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526
    //calculate differential pressure
    const float air_gas_constant = 287.1f; // J/(kg * K)
    const float absolute_null_celsius = -273.15f; // °C
    float density = abs_pressure / (air_gas_constant * (temperature - absolute_null_celsius));
    diff_pressure = true_airspeed * true_airspeed * density / 2.0f;
    //qDebug() << "diff_pressure: " << diff_pressure << "abs_pressure: " << abs_pressure;
    
    /* Calculate indicated airspeed */
    const float air_density_sea_level_15C  = 1.225f; //kg/m^3
    if (diff_pressure > 0)
    {
        ind_airspeed =  sqrtf((2.0f*diff_pressure) / air_density_sea_level_15C);
    } else
    {
        ind_airspeed =  -sqrtf((2.0f*fabsf(diff_pressure)) / air_density_sea_level_15C);
    }
    
    //qDebug() << "ind_airspeed: " << ind_airspeed << "true_airspeed: " << true_airspeed;
    
lm's avatar
lm committed
527
    // Send updated state
Thomas Gubler's avatar
Thomas Gubler committed
528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575
    //qDebug()  << "sensorHilEnabled: " << sensorHilEnabled;
    if (_sensorHilEnabled)
    {
        quint16 fields_changed = 0xFFF; //set all 12 used bits

        float pressure_alt = alt;

        xmag_ned = cosf(mag_variation);
        ymag_ned = sinf(mag_variation);
        zmag_ned = sinf(mag_dip);
        float tempMagLength = sqrtf(xmag_ned*xmag_ned + ymag_ned*ymag_ned + zmag_ned*zmag_ned);
        xmag_ned = xmag_ned / tempMagLength;
        ymag_ned = ymag_ned / tempMagLength;
        zmag_ned = zmag_ned / tempMagLength;

        //transform magnetic measurement to body frame coordinates
        double cosPhi = cos(roll);
        double sinPhi = sin(roll);
        double cosThe = cos(pitch);
        double sinThe = sin(pitch);
        double cosPsi = cos(yaw);
        double sinPsi = sin(yaw);

        float R_B_N[3][3];

        R_B_N[0][0] = cosThe * cosPsi;
        R_B_N[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
        R_B_N[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;

		R_B_N[1][0] = cosThe * sinPsi;
		R_B_N[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
		R_B_N[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;

		R_B_N[2][0] = -sinThe;
		R_B_N[2][1] = sinPhi * cosThe;
		R_B_N[2][2] = cosPhi * cosThe;

        Eigen::Matrix3f R_B_N_M = Eigen::Map<Eigen::Matrix3f>((float*)R_B_N).eval();

        Eigen::Vector3f mag_ned(xmag_ned, ymag_ned, zmag_ned);

        Eigen::Vector3f mag_body = R_B_N_M * mag_ned;

        xmag_body = mag_body(0);
        ymag_body = mag_body(1);
        zmag_body = mag_body(2);

        emit sensorHilRawImuChanged(QGC::groundTimeUsecs(), xacc, yacc, zacc, rollspeed, pitchspeed, yawspeed,
576
                                    xmag_body, ymag_body, zmag_body, abs_pressure*1e-2f, diff_pressure*1e-2f, pressure_alt, temperature, fields_changed); //Pressure in hPa for mavlink
Thomas Gubler's avatar
Thomas Gubler committed
577 578 579

//        qDebug()  << "sensorHilRawImuChanged " << xacc  << yacc << zacc  << rollspeed << pitchspeed << yawspeed << xmag << ymag << zmag << abs_pressure << diff_pressure << pressure_alt << temperature;
        int gps_fix_type = 3;
580 581
        float eph = 0.3f;
        float epv = 0.6f;
Thomas Gubler's avatar
Thomas Gubler committed
582 583 584 585 586 587 588 589 590
        float vel = sqrt(vx*vx + vy*vy + vz*vz);
        float cog = yaw;
        int satellites = 8;

        emit sensorHilGpsChanged(QGC::groundTimeUsecs(), lat, lon, alt, gps_fix_type, eph, epv, vel, vx, vy, vz, cog, satellites);

//        qDebug()  << "sensorHilGpsChanged " << lat  << lon << alt  << vel;
    } else {
        emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
lm's avatar
lm committed
591
                         pitchspeed, yawspeed, lat, lon, alt,
Thomas Gubler's avatar
Thomas Gubler committed
592 593 594
                         vx, vy, vz,
                         ind_airspeed, true_airspeed,
                         xacc, yacc, zacc);
595
        //qDebug()  << "hilStateChanged " << (qint32)lat << (qint32)lon << (qint32)alt;
Thomas Gubler's avatar
Thomas Gubler committed
596
    }
lm's avatar
lm committed
597 598 599 600 601 602 603 604 605 606

    //    // 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;
607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624
}


/**
 * @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
625
bool QGCFlightGearLink::disconnectSimulation()
626
{
LM's avatar
LM committed
627
    disconnect(process, SIGNAL(error(QProcess::ProcessError)),
628
               this, SLOT(processError(QProcess::ProcessError)));
629
    disconnect(mav, SIGNAL(hilControlsChanged(quint64, float, float, float, float, quint8, quint8)), this, SLOT(updateControls(quint64,float,float,float,float,quint8,quint8)));
Thomas Gubler's avatar
Thomas Gubler committed
630 631 632
    disconnect(this, SIGNAL(hilStateChanged(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)), mav, SLOT(sendHilState(quint64, float, float, float, float,float, float, double, double, double, float, float, float, float, float, float, float, float)));
    disconnect(this, SIGNAL(sensorHilGpsChanged(quint64, double, double, double, int, float, float, float, float, float, float, float, int)), mav, SLOT(sendHilGps(quint64, double, double, double, int, float, float, float, float, float, float, float, int)));
    disconnect(this, SIGNAL(sensorHilRawImuChanged(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)), mav, SLOT(sendHilSensors(quint64,float,float,float,float,float,float,float,float,float,float,float,float,float,quint32)));
LM's avatar
LM committed
633

LM's avatar
LM committed
634 635 636 637 638 639 640 641
    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
    if (socket)
    {
lm's avatar
lm committed
642
        socket->close();
LM's avatar
LM committed
643 644 645
        delete socket;
        socket = NULL;
    }
646 647 648

    connectState = false;

649 650
    emit simulationDisconnected();
    emit simulationConnected(false);
651 652 653
    return !connectState;
}

Don Gagne's avatar
Don Gagne committed
654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 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
/// @brief Splits a space seperated set of command line arguments into a QStringList.
///         Quoted strings are allowed and handled correctly.
/// @param uiArgs Arguments to parse
/// @param argList Returned argument list
/// @return Returns false if the argument list has mistmatced quotes within in.

bool QGCFlightGearLink::parseUIArguments(QString uiArgs, QStringList& argList)
{

	// This is not as easy as it seams since some options can be quoted to preserve spaces within things like
    // directories. There is likely some crazed regular expression which can do this. But after trying that
    // route I gave up and instead here is the code which does it the hard way. Another thing to be aware of
    // is that the QStringList passed to QProces::start is similar to what you would get in argv after the
    // command line is processed. This means that quoted strings have the quotes removed before making it to argv.
    
	bool inQuotedString = false;
	bool previousSpace = false;
	QString currentArg;
	for (int i=0; i<uiArgs.size(); i++) {
		const QChar chr = uiArgs[i];
        
		if (chr == ' ') {
			if (inQuotedString) {
				// Space is inside quoted string leave it in
				currentArg += chr;
				continue;
			} else {
				if (previousSpace) {
					// Disregard multiple spaces
					continue;
				} else {
					// We have a space that is finishing an argument
					previousSpace = true;
					if (inQuotedString) {
						MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Mismatched quotes in specified command line options"));
						return false;
					}
					if (!currentArg.isEmpty()) {
						argList += currentArg;
						currentArg.clear();
					}
				}
			}
		} else if (chr == '\"') {
			// Flip the state of being in a quoted string. Note that we specifically do not add the
			// quote to the string. This replicates standards command line parsing behaviour.
			if (chr == '\"') {
				inQuotedString = !inQuotedString;
			}
			previousSpace = false;
		} else {
			// Flip the state of being in a quoted string
			if (chr == '\"') {
				inQuotedString = !inQuotedString;
			}
			previousSpace = false;
			currentArg += chr;
		}
	}
	// We should never end parsing on an unterminated quote
	if (inQuotedString) {
		return false;
	}
    
	// Finish up last arg
	if (!currentArg.isEmpty()) {
		argList += currentArg;
		currentArg.clear();
	}
    
    return true;
}

727 728 729 730 731
/**
 * @brief Connect the connection.
 *
 * @return True if connection has been established, false if connection couldn't be established.
 **/
lm's avatar
lm committed
732
bool QGCFlightGearLink::connectSimulation()
733 734
{

735 736
    start(HighPriority);
    return true;
737 738
}

739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761
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;
   }
}

Thomas Gubler's avatar
Thomas Gubler committed
762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784
void QGCFlightGearLink::printFgfsOutput()
{
   qDebug() << "fgfs stdout:";
   QByteArray byteArray = process->readAllStandardOutput();
   QStringList strLines = QString(byteArray).split("\n");

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

void QGCFlightGearLink::printFgfsError()
{
   qDebug() << "fgfs stderr:";

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

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

785 786 787 788 789 790 791 792 793
/**
 * @brief Set the startup arguments used to start flightgear
 *
 **/
void QGCFlightGearLink::setStartupArguments(QString startupArguments)
{
    this->startupArguments = startupArguments;
}

794 795 796 797 798 799 800 801 802 803 804 805 806 807 808
/**
 * @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
809 810 811 812 813
QString QGCFlightGearLink::getRemoteHost()
{
    return QString("%1:%2").arg(currentHost.toString(), currentPort);
}

814 815 816
void QGCFlightGearLink::setName(QString name)
{
    this->name = name;
lm's avatar
lm committed
817
    //    emit nameChanged(this->name);
818
}
819 820 821 822 823

void QGCFlightGearLink::setBarometerOffset(float barometerOffsetkPa)
{
    this->barometerOffsetkPa = barometerOffsetkPa;
}