diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index eddd7a5d460adf09f7d4b4258020013047bbe696..df3b4515671f3335efcd01f85af1ced238fd3ef2 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -76,6 +76,217 @@ QGCFlightGearLink::~QGCFlightGearLink() **/ void QGCFlightGearLink::run() { + qDebug() << "STARTING FLIGHTGEAR LINK"; + + if (!mav) return; + socket = new QUdpSocket(this); + connectState = socket->bind(host, port); + + QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); + + process = new QProcess(this); + terraSync = new QProcess(this); + + 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(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(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; + exec(); } @@ -446,220 +657,9 @@ bool QGCFlightGearLink::disconnectSimulation() **/ bool QGCFlightGearLink::connectSimulation() { - qDebug() << "STARTING FLIGHTGEAR LINK"; - if (!mav) return false; - socket = new QUdpSocket(this); - connectState = socket->bind(host, port); - - QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); - - process = new QProcess(this); - terraSync = new QProcess(this); - - 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(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(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 false; - - // --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; - - - start(LowPriority); - return connectState; + start(HighPriority); + return true; } void QGCFlightGearLink::printTerraSyncOutput() diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index 7b56249db15ede3eef6496714a20ee7a21c04791..ffe29e610e5d3da2337416cfa216aa1a4cf4c11a 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -71,6 +71,89 @@ QGCJSBSimLink::~QGCJSBSimLink() **/ void QGCJSBSimLink::run() { + qDebug() << "STARTING FLIGHTGEAR LINK"; + + if (!mav) return; + socket = new QUdpSocket(this); + connectState = socket->bind(host, port); + + QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); + + process = new QProcess(this); + + 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(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))); + + + UAS* uas = dynamic_cast(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))); + + // Start Flightgear + QStringList arguments; + QString processJSB; + QString rootJSB; + +#ifdef Q_OS_MACX + processJSB = "/usr/local/bin/JSBSim"; + rootJSB = "/Applications/FlightGear.app/Contents/Resources/data"; +#endif + +#ifdef Q_OS_WIN32 + processJSB = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs"; + rootJSB = "C:\\Program Files (x86)\\FlightGear\\data"; +#endif + +#ifdef Q_OS_LINUX + processJSB = "/usr/games/fgfs"; + rootJSB = "/usr/share/games/flightgear"; +#endif + + // Sanity checks + bool sane = true; + QFileInfo executable(processJSB); + if (!executable.isExecutable()) + { + MainWindow::instance()->showCriticalMessage(tr("JSBSim Failed to Start"), tr("JSBSim was not found at %1").arg(processJSB)); + sane = false; + } + + QFileInfo root(rootJSB); + if (!root.isDir()) + { + MainWindow::instance()->showCriticalMessage(tr("JSBSim Failed to Start"), tr("JSBSim data directory was not found at %1").arg(rootJSB)); + sane = false; + } + + if (!sane) return; + + /*Prepare JSBSim Arguments */ + + if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + { + arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); + } + else + { + arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); + } + + process->start(processJSB, arguments); + + emit simulationConnected(connectState); + if (connectState) { + emit simulationConnected(); + connectionStartTime = QGC::groundTimeUsecs()/1000; + } + qDebug() << "STARTING SIM"; + exec(); } @@ -303,91 +386,8 @@ bool QGCJSBSimLink::disconnectSimulation() **/ bool QGCJSBSimLink::connectSimulation() { - qDebug() << "STARTING FLIGHTGEAR LINK"; - - if (!mav) return false; - socket = new QUdpSocket(this); - connectState = socket->bind(host, port); - - QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); - - process = new QProcess(this); - - 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(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))); - - - UAS* uas = dynamic_cast(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))); - - // Start Flightgear - QStringList arguments; - QString processJSB; - QString rootJSB; - -#ifdef Q_OS_MACX - processJSB = "/usr/local/bin/JSBSim"; - rootJSB = "/Applications/FlightGear.app/Contents/Resources/data"; -#endif - -#ifdef Q_OS_WIN32 - processJSB = "C:\\Program Files (x86)\\FlightGear\\bin\\Win32\\fgfs"; - rootJSB = "C:\\Program Files (x86)\\FlightGear\\data"; -#endif - -#ifdef Q_OS_LINUX - processJSB = "/usr/games/fgfs"; - rootJSB = "/usr/share/games/flightgear"; -#endif - - // Sanity checks - bool sane = true; - QFileInfo executable(processJSB); - if (!executable.isExecutable()) - { - MainWindow::instance()->showCriticalMessage(tr("JSBSim Failed to Start"), tr("JSBSim was not found at %1").arg(processJSB)); - sane = false; - } - - QFileInfo root(rootJSB); - if (!root.isDir()) - { - MainWindow::instance()->showCriticalMessage(tr("JSBSim Failed to Start"), tr("JSBSim data directory was not found at %1").arg(rootJSB)); - sane = false; - } - - if (!sane) return false; - - /*Prepare JSBSim Arguments */ - - if (mav->getSystemType() == MAV_TYPE_QUADROTOR) - { - arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); - } - else - { - arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script); - } - - process->start(processJSB, arguments); - - emit simulationConnected(connectState); - if (connectState) { - emit simulationConnected(); - connectionStartTime = QGC::groundTimeUsecs()/1000; - } - qDebug() << "STARTING SIM"; - - start(LowPriority); - return connectState; + start(HighPriority); + return true; } /** diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index e2aa4abc635d91ece3c95511062d01d9da553ecb..355cf0af2bb24b7ec6e5ae0b23051316d99ef385 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -144,9 +144,72 @@ void QGCXPlaneLink::setVersion(unsigned int version) **/ void QGCXPlaneLink::run() { - forever { - QGC::SLEEP::usleep(500000); + if (!mav) return; + if (connectState) return; + + socket = new QUdpSocket(this); + connectState = socket->bind(localHost, localPort); + if (!connectState) return; + + QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); + + 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(mav, SIGNAL(hilActuatorsChanged(uint64_t, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(uint64_t,float,float,float,float,float,float,float,float))); + + connect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); + 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(mav); + if (uas) + { + uas->startHil(); + } + +#pragma pack(push, 1) + struct iset_struct + { + char b[5]; + int index; // (0->20 in the lsit below) + char str_ipad_them[16]; + char str_port_them[6]; + char padding[2]; + int use_ip; + } ip; // to use this option, 0 not to. +#pragma pack(pop) + + ip.b[0] = 'I'; + ip.b[1] = 'S'; + ip.b[2] = 'E'; + ip.b[3] = 'T'; + ip.b[4] = '0'; + + QList hostAddresses = QNetworkInterface::allAddresses(); + + QString localAddrStr; + QString localPortStr = QString("%1").arg(localPort); + + for (int i = 0; i < hostAddresses.size(); i++) + { + // Exclude loopback IPv4 and all IPv6 addresses + if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":")) + { + localAddrStr = hostAddresses.at(i).toString(); + break; + } } + + //qDebug() << "REQ SEND TO:" << localAddrStr << localPortStr; + + ip.index = 0; + strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16)); + strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6)); + ip.use_ip = 1; + + writeBytes((const char*)&ip, sizeof(ip)); + + exec(); } void QGCXPlaneLink::setPort(int localPort) @@ -945,73 +1008,9 @@ bool QGCXPlaneLink::connectSimulation() // XXX Hack storeSettings(); - start(LowPriority); - - if (!mav) return false; - if (connectState) return false; + start(HighPriority); - socket = new QUdpSocket(this); - connectState = socket->bind(localHost, localPort); - if (!connectState) return false; - - QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); - - 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(mav, SIGNAL(hilActuatorsChanged(uint64_t, float, float, float, float, float, float, float, float)), this, SLOT(updateActuators(uint64_t,float,float,float,float,float,float,float,float))); - - connect(this, SIGNAL(hilGroundTruthChanged(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float)), mav, SLOT(sendHilGroundTruth(quint64,float,float,float,float,float,float,double,double,double,float,float,float,float,float,float,float,float))); - 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(mav); - if (uas) - { - uas->startHil(); - } - -#pragma pack(push, 1) - struct iset_struct - { - char b[5]; - int index; // (0->20 in the lsit below) - char str_ipad_them[16]; - char str_port_them[6]; - char padding[2]; - int use_ip; - } ip; // to use this option, 0 not to. -#pragma pack(pop) - - ip.b[0] = 'I'; - ip.b[1] = 'S'; - ip.b[2] = 'E'; - ip.b[3] = 'T'; - ip.b[4] = '0'; - - QList hostAddresses = QNetworkInterface::allAddresses(); - - QString localAddrStr; - QString localPortStr = QString("%1").arg(localPort); - - for (int i = 0; i < hostAddresses.size(); i++) - { - // Exclude loopback IPv4 and all IPv6 addresses - if (hostAddresses.at(i) != QHostAddress("127.0.0.1") && !hostAddresses.at(i).toString().contains(":")) - { - localAddrStr = hostAddresses.at(i).toString(); - break; - } - } - - //qDebug() << "REQ SEND TO:" << localAddrStr << localPortStr; - - ip.index = 0; - strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16)); - strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6)); - ip.use_ip = 1; - - writeBytes((const char*)&ip, sizeof(ip)); - return connectState; + return true; } /** diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index a8964db6ca2c55c84ee86b2f586e6c7705c1b5eb..392edbfcbb8e7be4961e16ab9ef4c6696ebc6015 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -61,6 +61,8 @@ TCPLink::~TCPLink() void TCPLink::run() { + _hardwareConnect(); + exec(); } @@ -214,11 +216,10 @@ bool TCPLink::connect() quit(); wait(); } - bool connected = _hardwareConnect(); - if (connected) { - start(HighPriority); - } - return connected; + + start(HighPriority); + + return true; } bool TCPLink::_hardwareConnect(void) diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 61f0c5d4b8bbfce27be8a5c21a225bcc6e63968d..7c401c73402bffc4dc4d6e6dfa6c0e6c4bff5104 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -69,9 +69,9 @@ UDPLink::~UDPLink() **/ void UDPLink::run() { - forever { - QGC::SLEEP::usleep(500000); - } + hardwareConnect(); + + exec(); } void UDPLink::setAddress(QHostAddress host) @@ -307,7 +307,7 @@ bool UDPLink::connect() this->quit(); this->wait(); } - bool connected = this->hardwareConnect(); + bool connected = true; start(HighPriority); return connected; }