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

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
 *   @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
39
#include "MainWindow.h"
40

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

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

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

void QGCFlightGearLink::setPort(int port)
{
    this->port = port;
lm's avatar
lm committed
69 70
    disconnectSimulation();
    connectSimulation();
71 72
}

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

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
/**
 * @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
124
            currentPort = host.split(":").last().toInt();
125 126 127 128 129 130 131 132 133 134 135 136 137
        }
    }
    else
    {
        QHostInfo info = QHostInfo::fromName(host);
        if (info.error() == QHostInfo::NoError)
        {
            // Add host
            currentHost = info.addresses().first();
        }
    }
}

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

lm's avatar
lm committed
142
    //float magnetos = 3.0f;
lm's avatar
lm committed
143 144 145
    Q_UNUSED(time);
    Q_UNUSED(systemMode);
    Q_UNUSED(navMode);
LM's avatar
LM committed
146

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

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

/**
 * @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
197 198 199

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

lm's avatar
lm committed
202 203 204 205 206 207 208 209 210
    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
211 212

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

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


/**
 * @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
272
bool QGCFlightGearLink::disconnectSimulation()
273
{
LM's avatar
LM committed
274
    disconnect(process, SIGNAL(error(QProcess::ProcessError)),
275
               this, SLOT(processError(QProcess::ProcessError)));
LM's avatar
LM committed
276 277 278
    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
279 280 281 282 283 284 285 286 287 288 289
    if (process)
    {
        process->close();
        delete process;
        process = NULL;
    }
    if (socket)
    {
        delete socket;
        socket = NULL;
    }
290 291 292

    connectState = false;

lm's avatar
lm committed
293 294
    emit flightGearDisconnected();
    emit flightGearConnected(false);
295 296 297 298 299 300 301 302
    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
303
bool QGCFlightGearLink::connectSimulation()
304
{
lm's avatar
lm committed
305
    if (!mav) return false;
306 307 308 309 310
    socket = new QUdpSocket(this);
    connectState = socket->bind(host, port);

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

lm's avatar
lm committed
311
    process = new QProcess(this);
lm's avatar
lm committed
312

lm's avatar
lm committed
313 314
    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)));
315

lm's avatar
lm committed
316 317 318 319
    //connect(&refreshTimer, SIGNAL(timeout()), this, SLOT(sendUAVUpdate()));
    // Catch process error
    QObject::connect( process, SIGNAL(error(QProcess::ProcessError)),
                      this, SLOT(processError(QProcess::ProcessError)));
320 321 322 323 324 325
    // Start Flightgear
    QStringList processCall;
    QString processFgfs;
    QString fgRoot;
    QString fgScenery;
    QString aircraft("Rascal110-JSBSim");
lm's avatar
lm committed
326 327

#ifdef Q_OS_MACX
328 329
    processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs";
    fgRoot = "--fg-root=/Applications/FlightGear.app/Contents/Resources/data";
330
    fgScenery = "--fg-scenery=/Applications/FlightGear.app/Contents/Resources/data/Scenery:/Applications/FlightGear.app/Contents/Resources/data/Scenery-Terrasync";
lm's avatar
lm committed
331 332 333
#endif

#ifdef Q_OS_WIN32
334 335
    processFgfs = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs";
    fgRoot = "--fg-root=C:\\Program Files (x86)\\FlightGear\\data";
lm's avatar
lm committed
336 337
#endif

LM's avatar
LM committed
338
#ifdef Q_OS_LINUX
339 340
    processFgfs = "fgfs";
    fgRoot = "--fg-root=/usr/share/flightgear/data";
LM's avatar
LM committed
341 342
#endif

343 344 345 346 347 348 349 350 351 352
    processCall << fgRoot;
    processCall << fgScenery;
    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 << "--in-air";
    processCall << "--vc=90";
    processCall << "--heading=300";
    processCall << "--timeofday=noon";
    processCall << "--disable-hud-3d";
    processCall << "--disable-fullscreen";
353 354 355 356
//    processCall << "--control=mouse";
//    processCall << "--disable-intro-music";
//    processCall << "--disable-sound";
//    processCall << "--disable-anti-alias-hud";
lm's avatar
lm committed
357 358 359
//    processCall << "--disable-random-objects";
//    processCall << "--disable-ai-models";
//    processCall << "--wind=0@0";
360
    processCall << "--fdm=jsb";
lm's avatar
lm committed
361 362
    processCall << "--prop:/engines/engine/running=true";
    processCall << "--units-meters";
363 364 365 366 367 368 369
    if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
    {
        // Start the remaining three motors of the quad
        processCall << "--prop:/engines/engine[1]/running=true";
        processCall << "--prop:/engines/engine[2]/running=true";
        processCall << "--prop:/engines/engine[3]/running=true";
    }
370 371 372
    processCall << QString("--lat=%1").arg(UASManager::instance()->getHomeLatitude());
    processCall << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude());
    processCall << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude());
373 374
    // Add new argument with this: processCall << "";
    processCall << QString("--aircraft=%2").arg(aircraft);
lm's avatar
lm committed
375

lm's avatar
lm committed
376
    process->start(processFgfs, processCall);
lm's avatar
lm committed
377 378


LM's avatar
LM committed
379

lm's avatar
lm committed
380 381 382 383 384 385
    emit flightGearConnected(connectState);
    if (connectState) {
        emit flightGearConnected();
        connectionStartTime = QGC::groundTimeUsecs()/1000;
    }
    qDebug() << "STARTING SIM";
LM's avatar
LM committed
386 387

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

lm's avatar
lm committed
389
    start(LowPriority);
390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410
    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
411
    //    emit nameChanged(this->name);
412
}