diff --git a/files/px4/parameter_tooltips/tooltips.txt b/files/px4/parameter_tooltips/tooltips.txt index d72273ccdb6329716600419265b05528a2a36975..854f5a0162b25c750085b561f4a88b33ab53282c 100644 --- a/files/px4/parameter_tooltips/tooltips.txt +++ b/files/px4/parameter_tooltips/tooltips.txt @@ -4,4 +4,8 @@ | BAT_N_CELLS | 1 | 100 | 3 | 1 | 1 | Number of SERIAL battery cells. Typically this ranges from 2S to 6S in small-scale UAVs | | BAT_V_SCALING | 0.001 | 1.0 | 0.00838 | 1 | 1 | Conversion from ADC ticks to battery voltage. Depends on the connected board, calibrate with a multimeter. | | MC_ATTRATE_P | 0.0 | 20.0 | 0.20 | 1 | 1 | Multirotor attitude rate control P gain. This gain controls how much of the motor thrust should be used to control angular velocity. A larger number will increase the control response, but will make the system also more twitchy. | -| FW_ROLLRATE_P | 0.0 | 20.0 | 0.30 | 1 | 1 | Fixed wing roll rate control P gain. This gain controls how strong the ailerons or rudder should be actuated in order to achieve a certain roll rate. A larger number will increase the control response, but will make the system also more twitchy. | \ No newline at end of file +| MC_ATTRATE_D | 0.0 | 20.0 | 0.05 | 1 | 1 | Multirotor attitude rate control D gain. A large value will allow to damp oscillations due to a high P gain, but will make the system response suspectible to noise.| +| MC_ATT_P | 0.0 | 20.0 | 0.20 | 1 | 1 | Multirotor attitude control proportional (P) gain. This defines how strong the response of the system will be to an attitude error| +| MC_ATT_D | 0.0 | 20.0 | 0.05 | 1 | 1 | Multirotor attitude control D gain. A large value will allow to damp oscillations due to a high P gain, but will make the system response suspectible to noise.| +| FW_ROLLRATE_P | 0.0 | 20.0 | 0.30 | 1 | 1 | Fixed wing roll rate control P gain. This gain controls how strong the ailerons or rudder should be actuated in order to achieve a certain roll rate. A larger number will increase the control response, but will make the system also more twitchy. | +| FW_HEADING_P | 0.0 | 20.0 | 4.00 | 1 | 1 | Fixed wing heading error to bank angle gain | \ No newline at end of file diff --git a/files/styles/style-indoor.css b/files/styles/style-indoor.css index f9571e7bb2468f9cb30941b6afb42bc434efd8d1..dc4d4dee8dae97ab3eba18173aa1620531a686fc 100644 --- a/files/styles/style-indoor.css +++ b/files/styles/style-indoor.css @@ -96,46 +96,39 @@ border: 1px solid #777777; margin-top: 1ex; /* leave space at the top for the title */ } - QDockWidget { - border: 1px solid #32345E; - /* titlebar-close-icon: url(close.png); - titlebar-normal-icon: url(undock.png);*/ - } - - QDockWidget::title { - text-align: left; /* align the text to the left */ - background: lightgray; - padding-left: 5px; - } - - QDockWidget::close-button, QDockWidget::float-button { - border: 1px solid transparent; - background: darkgray; - padding: 0px; - } +QDockWidget::close-button, QDockWidget::float-button { + border: 1px solid transparent; + background: none; + padding: 0px; +} - QDockWidget::close-button:hover, QDockWidget::float-button:hover { - background: gray; - } +QDockWidget::close-button:hover, QDockWidget::float-button:hover { + background: none; +} - QDockWidget::close-button:pressed, QDockWidget::float-button:pressed { +QDockWidget::close-button:pressed, QDockWidget::float-button:pressed { padding: 1px -1px -1px 1px; - } - - + background: none; +} -QDockWidget::close-button, QDockWidget::float-button { - background-color: #181820; - color: #EEEEEE; + QDockWidget { + border: 10px solid #66666B; + padding: 2px; + margin: 1px; + border-radius: 1px; + /*background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #59666f, stop: 1 #414B52);*/ + /* titlebar-close-icon: url(close.png); + titlebar-normal-icon: url(undock.png);*/ } QDockWidget::title { text-align: left; - background: #121214; - color: #4A4A4F; - padding-left: 5px; - height: 10px; - border-bottom: 1px solid #555555; + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #3F556A, stop: 1 #293645); + color: #EDEDED; + padding-left: 10px; + height: 14px; + border-bottom: 1px solid #1B1F22; + border-bottom: 2px solid #2C3A4A; } QSeparator { @@ -190,31 +183,36 @@ QPushButton { min-height: 18px; max-height: 18px; min-width: 60px;*/ - border: 2px solid #4A4A4F; - border-radius: 3px; + min-height: 20px; + /*min-width: 24px;*/ + max-height: 20px; + border: 0px solid #59666f; + border-radius: 2px; padding-left: 8px; padding-right: 8px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #59666f, stop: 1 #414B52); } QPushButton:checked { background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #404040, stop: 1 #808080); - border: 2px solid #379AC3; + border: 0px solid #379AC3; } QPushButton:pressed { background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); - border: 2px solid #379AC3; + border: 0px solid #379AC3; } QToolButton { font-weight: bold; - min-height: 18px; - min-width: 24px; - max-height: 18px; - border: 2px solid #4A4A4F; - border-radius: 3px; - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #232228, stop: 1 #020208); + min-height: 20px; + /*min-width: 24px;*/ + max-height: 20px; + border: 0px solid #4A4A4F; + border-radius: 2px; + padding-left: 3px; + padding-right: 3px; + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #59666f, stop: 1 #414B52); } QToolButton:checked { @@ -228,8 +226,9 @@ QToolButton:pressed { } QToolTip { - background-color: #090909; - border: 1px solid #379AC3; + background-color: #3D5368; + border: 0px solid #379AC3; + margin: 3px; border-radius: 3px; color: #DDDDDF; } @@ -400,11 +399,11 @@ QDialog { /* Style the tab using the tab sub-control. Note that it reads QTabBar _not_ QTabWidget */ QTabBar::tab { - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535); + background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #090909, stop: 1 #353535); border: 2px solid #62676B; - border-radius: 4px; - min-width: 8ex; - padding: 2px; + border-radius: 4px; + min-width: 8ex; + padding: 2px; } QTabBar::tab:selected, QTabBar::tab:hover { diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index f5edd480df9274dae8f363e177003ae483437a11..a49a7a51c8abdcc3c01561e234506632f885dbbb 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -224,7 +224,9 @@ FORMS += src/ui/MainWindow.ui \ src/ui/mission/QGCMissionDoStartSearch.ui \ src/ui/mission/QGCMissionDoFinishSearch.ui \ src/ui/QGCVehicleConfig.ui \ - src/ui/QGCHilConfiguration.ui + src/ui/QGCHilConfiguration.ui \ + src/ui/QGCHilFlightGearConfiguration.ui \ + src/ui/QGCHilXPlaneConfiguration.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -362,7 +364,9 @@ HEADERS += src/MG.h \ src/ui/mission/QGCMissionDoFinishSearch.h \ src/ui/QGCVehicleConfig.h \ src/comm/QGCHilLink.h \ - src/ui/QGCHilConfiguration.h + src/ui/QGCHilConfiguration.h \ + src/ui/QGCHilFlightGearConfiguration.h \ + src/ui/QGCHilXPlaneConfiguration.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -520,7 +524,9 @@ SOURCES += src/main.cc \ src/ui/mission/QGCMissionDoFinishSearch.cc \ src/ui/QGCVehicleConfig.cc \ src/comm/QGCHilLink.cc \ - src/ui/QGCHilConfiguration.cc + src/ui/QGCHilConfiguration.cc \ + src/ui/QGCHilFlightGearConfiguration.cc \ + src/ui/QGCHilXPlaneConfiguration.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index bc69a949da6304b6194d5461fa9e70389089c6b2..279e66582747c951ee9ae9010de58959867873db 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -39,9 +39,11 @@ This file is part of the QGROUNDCONTROL project #include #include "MainWindow.h" -QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString remoteHost, QHostAddress host, quint16 port) : +QGCFlightGearLink::QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost, QHostAddress host, quint16 port) : process(NULL), terraSync(NULL), + socket(NULL), + startupArguments(startupArguments), flightGearVersion(0) { this->host = host; @@ -349,20 +351,7 @@ bool QGCFlightGearLink::connectSimulation() QString fgRoot; QString fgScenery; QString terraSyncScenery; - 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"; - } + QString fgAircraft; #ifdef Q_OS_MACX processFgfs = "/Applications/FlightGear.app/Contents/Resources/fgfs"; @@ -387,6 +376,8 @@ bool QGCFlightGearLink::connectSimulation() 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); @@ -426,6 +417,7 @@ bool QGCFlightGearLink::connectSimulation() /*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) { // FIXME ADD QUAD-Specific protocol here @@ -438,35 +430,37 @@ bool QGCFlightGearLink::connectSimulation() flightGearArguments << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").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 << "--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 @@ -483,7 +477,7 @@ bool QGCFlightGearLink::connectSimulation() flightGearArguments << QString("--lon=%1").arg(UASManager::instance()->getHomeLongitude()); flightGearArguments << QString("--altitude=%1").arg(UASManager::instance()->getHomeAltitude()); // Add new argument with this: flightGearArguments << ""; - flightGearArguments << QString("--aircraft=%2").arg(aircraft); + //flightGearArguments << QString("--aircraft=%2").arg(aircraft); /*Prepare TerraSync Arguments */ QStringList terraSyncArguments; @@ -542,6 +536,15 @@ void QGCFlightGearLink::printTerraSyncError() } } +/** + * @brief Set the startup arguments used to start flightgear + * + **/ +void QGCFlightGearLink::setStartupArguments(QString startupArguments) +{ + this->startupArguments = startupArguments; +} + /** * @brief Check if connection is active. * diff --git a/src/comm/QGCFlightGearLink.h b/src/comm/QGCFlightGearLink.h index ca159bdf8106a60a663708473609c34aecec22dc..f8cbb2628c99fa2be99e3f99d242d7836544679f 100644 --- a/src/comm/QGCFlightGearLink.h +++ b/src/comm/QGCFlightGearLink.h @@ -49,7 +49,7 @@ class QGCFlightGearLink : public QGCHilLink //Q_INTERFACES(QGCFlightGearLinkInterface:LinkInterface) public: - QGCFlightGearLink(UASInterface* mav, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); + QGCFlightGearLink(UASInterface* mav, QString startupArguments, QString remoteHost=QString("127.0.0.1:49000"), QHostAddress host = QHostAddress::Any, quint16 port = 49005); ~QGCFlightGearLink(); bool isConnected(); @@ -99,6 +99,11 @@ public slots: Q_UNUSED(version); } + void selectAirframe(const QString& airframe) + { + Q_UNUSED(airframe); + } + void readBytes(); /** * @brief Write a number of bytes to the interface. @@ -112,6 +117,7 @@ public slots: void printTerraSyncOutput(); void printTerraSyncError(); + void setStartupArguments(QString startupArguments); protected: QString name; @@ -137,6 +143,7 @@ protected: QProcess* process; QProcess* terraSync; unsigned int flightGearVersion; + QString startupArguments; void setName(QString name); diff --git a/src/comm/QGCHilLink.h b/src/comm/QGCHilLink.h index c4319be47d5aa5abcd7dbc186945b227dc68849c..4d79e9c9f4cc450b5d7aa2cdc041b210da11b480 100644 --- a/src/comm/QGCHilLink.h +++ b/src/comm/QGCHilLink.h @@ -48,6 +48,8 @@ public slots: /** @brief Set the simulator version as text string */ virtual void setVersion(const QString& version) = 0; + virtual void selectAirframe(const QString& airframe) = 0; + virtual void readBytes() = 0; /** * @brief Write a number of bytes to the interface. diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index 7a4019684070643c9992113599135fc3da1bfcfb..723a980738446352b0b8859905986ccac3f648f3 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -75,7 +75,7 @@ void QGCXPlaneLink::loadSettings() settings.beginGroup("QGC_XPLANE_LINK"); setRemoteHost(settings.value("REMOTE_HOST", QString("%1:%2").arg(remoteHost.toString()).arg(remotePort)).toString()); setVersion(settings.value("XPLANE_VERSION", 10).toInt()); - selectPlane(settings.value("AIRFRAME", "default").toString()); + selectAirframe(settings.value("AIRFRAME", "default").toString()); settings.endGroup(); } @@ -182,7 +182,6 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost) if (newHost.contains(":")) { - //qDebug() << "HOST: " << newHost.split(":").first(); QHostInfo info = QHostInfo::fromName(newHost.split(":").first()); if (info.error() == QHostInfo::NoError) { @@ -198,7 +197,6 @@ void QGCXPlaneLink::setRemoteHost(const QString& newHost) } } remoteHost = address; - //qDebug() << "Address:" << address.toString(); // Set localPort according to user input remotePort = newHost.split(":").last().toInt(); } @@ -586,7 +584,7 @@ bool QGCXPlaneLink::disconnectSimulation() return !connectState; } -void QGCXPlaneLink::selectPlane(const QString& plane) +void QGCXPlaneLink::selectAirframe(const QString& plane) { airframeName = plane; @@ -718,6 +716,8 @@ void QGCXPlaneLink::setRandomAttitude() bool QGCXPlaneLink::connectSimulation() { qDebug() << "STARTING X-PLANE LINK, CONNECTING TO" << remoteHost << ":" << remotePort; + // XXX Hack + storeSettings(); start(LowPriority); @@ -730,9 +730,6 @@ bool QGCXPlaneLink::connectSimulation() 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(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(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))); diff --git a/src/comm/QGCXPlaneLink.h b/src/comm/QGCXPlaneLink.h index f2f202a7704987976f93977d6d2800a92a031ddf..e389b7b8f2669f9f45ae0d0d6a7068e32bffe6aa 100644 --- a/src/comm/QGCXPlaneLink.h +++ b/src/comm/QGCXPlaneLink.h @@ -130,7 +130,7 @@ public slots: * @brief Select airplane model * @param plane the name of the airplane */ - void selectPlane(const QString& plane); + void selectAirframe(const QString& airframe); /** * @brief Set the airplane position and attitude * @param lat diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index 5155db5287be7b6d7f5e1659d21ca98cb86fd558..069edc8a8c77a68520d654dcca892b4ebc82616d 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -42,7 +42,7 @@ public: virtual double getParamMin(const QString& param) = 0; virtual double getParamMax(const QString& param) = 0; virtual double getParamDefault(const QString& param) = 0; - virtual const QString& getParamInfo(const QString& param) = 0; + virtual QString getParamInfo(const QString& param) = 0; /** @brief Request an update for the parameter list */ void requestParameterListUpdate(int component = 0); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index afb846af6d948c2af586135a2808eea8b0d57947..3dbb6a47663c395934e5a6e404948084dd500751 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -97,7 +97,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), paramManager(NULL), attitudeStamped(false), lastAttitude(0), - simulation(new QGCXPlaneLink(this)), + simulation(0), isLocalPositionKnown(false), isGlobalPositionKnown(false), systemIsArmed(false), @@ -2263,18 +2263,13 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v for (unsigned int i = 0; i < sizeof(p.param_id); i++) { // String characters - if ((int)i < id.length() && i < (sizeof(p.param_id) - 1)) + if ((int)i < id.length()) { p.param_id[i] = id.toAscii()[i]; } - // // Null termination at end of string or end of buffer - // else if ((int)i == id.length() || i == (sizeof(p.param_id) - 1)) - // { - // p.param_id[i] = '\0'; - // } - // Zero fill else { + // Fill rest with zeros p.param_id[i] = 0; } } @@ -2588,14 +2583,24 @@ bool UAS::emergencyKILL() } /** -* If enabled, connect the fligth gear link. +* If enabled, connect the flight gear link. */ -void UAS::enableHilFlightGear(bool enable) -{ +void UAS::enableHilFlightGear(bool enable, QString options) +{ + QGCFlightGearLink* link = dynamic_cast(simulation); + if (!link || !simulation) { + // Delete wrong sim + if (simulation) { + stopHil(); + delete simulation; + } + simulation = new QGCFlightGearLink(this, options); + } // Connect Flight Gear Link + link = dynamic_cast(simulation); + link->setStartupArguments(options); if (enable) { - simulation = new QGCFlightGearLink(this); startHil(); } else @@ -2605,11 +2610,20 @@ void UAS::enableHilFlightGear(bool enable) } /** -* If enabled, connect the fligth gear link. +* If enabled, connect the X-plane gear link. */ void UAS::enableHilXPlane(bool enable) { - // Connect Flight Gear Link + QGCXPlaneLink* link = dynamic_cast(simulation); + if (!link || !simulation) { + if (simulation) { + stopHil(); + delete simulation; + } + qDebug() << "CREATED NEW XPLANE LINK"; + simulation = new QGCXPlaneLink(this); + } + // Connect X-Plane Link if (enable) { startHil(); @@ -2679,7 +2693,7 @@ void UAS::startHil() */ void UAS::stopHil() { - simulation->disconnectSimulation(); + if (simulation) simulation->disconnectSimulation(); mavlink_message_t msg; mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & !MAV_MODE_FLAG_HIL_ENABLED, navMode); sendMessage(msg); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 1030bd4b00cf928bbeb7ef835c824effdb937518..478edf60b7a5fa4645c67b01d1f01bda26d62b08 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -531,7 +531,7 @@ public slots: void go(); /** @brief Enable / disable HIL */ - void enableHilFlightGear(bool enable); + void enableHilFlightGear(bool enable, QString options); void enableHilXPlane(bool enable); diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index eacb95d87412f42357bb5d75d53304a665086580..8162cb6f76f4747c4f85e0b44bffb5d13962d80c 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -108,8 +108,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) : laserFix(0), iruFix(0), mavInitialized(false), - topMargin(12.0f), - bottomMargin(10.0f), + topMargin(18.0f), + bottomMargin(12.0f), attControlKnown(false), xyControlKnown(false), zControlKnown(false), diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 2bef0bb8372b99e4e0a3e356d8db228addbb1227..6e626da2c18f0a329d92dd9de504b165230a32c0 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -70,7 +70,7 @@ HUD::HUD(int width, int height, QWidget* parent) yCenterOffset(0.0f), vwidth(200.0f), vheight(150.0f), - vGaugeSpacing(50.0f), + vGaugeSpacing(65.0f), vPitchPerDeg(6.0f), ///< 4 mm y translation per degree) rawBuffer1(NULL), rawBuffer2(NULL), @@ -335,7 +335,7 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p void HUD::updateBattery(UASInterface* uas, double voltage, double percent, int seconds) { Q_UNUSED(uas); - fuelStatus = tr("BAT [%1% | %2V] (%3:%4)").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0')).arg(seconds/60, 2, 10, QChar('0')).arg(seconds%60, 2, 10, QChar('0')); + fuelStatus = tr("BAT [%1% | %2V]").arg(percent, 2, 'f', 0, QChar('0')).arg(voltage, 4, 'f', 1, QChar('0')); if (percent < 20.0f) { fuelColor = warningColor; } else if (percent < 10.0f) { @@ -622,7 +622,7 @@ void HUD::paintHUD() // Low-pass roll, pitch and yaw rollLP = roll;//rollLP * 0.2f + 0.8f * roll; pitchLP = pitch;//pitchLP * 0.2f + 0.8f * pitch; - yawLP = yaw;//yawLP * 0.2f + 0.8f * yaw; + yawLP = (!isinf(yaw) && !isnan(yaw)) ? yaw : yawLP;//yawLP * 0.2f + 0.8f * yaw; // Translate for yaw const float maxYawTrans = 60.0f; @@ -650,6 +650,8 @@ void HUD::paintHUD() // Negate to correct direction yawTrans = -yawTrans; + yawTrans = 0; + //qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw; // Update scaling factor @@ -714,20 +716,20 @@ void HUD::paintHUD() painter.setRenderHint(QPainter::HighQualityAntialiasing, true); painter.translate((this->vwidth/2.0+xCenterOffset)*scalingFactor, (this->vheight/2.0+yCenterOffset)*scalingFactor); - - // COORDINATE FRAME IS NOW (0,0) at CENTER OF WIDGET // Draw all fixed indicators - // MODE - paintText(mode, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 10, &painter); - // STATE - paintText(state, infoColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 15, &painter); // BATTERY - paintText(fuelStatus, fuelColor, 2.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 20, &painter); + paintText(fuelStatus, fuelColor, 6.0f, (-vwidth/2.0) + 10, -vheight/2.0 + 6, &painter); // Waypoint - paintText(waypointName, defaultColor, 2.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter); + paintText(waypointName, defaultColor, 6.0f, (-vwidth/3.0) + 10, +vheight/3.0 + 15, &painter); + + QPen linePen(Qt::SolidLine); + linePen.setWidth(refLineWidthToPen(1.0f)); + linePen.setColor(defaultColor); + painter.setBrush(Qt::NoBrush); + painter.setPen(linePen); // YAW INDICATOR // @@ -735,15 +737,15 @@ void HUD::paintHUD() // . . // ....... // - const float yawIndicatorWidth = 4.0f; - const float yawIndicatorY = vheight/2.0f - 10.0f; + const float yawIndicatorWidth = 12.0f; + const float yawIndicatorY = vheight/2.0f - 15.0f; QPolygon yawIndicator(4); yawIndicator.setPoint(0, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY))); yawIndicator.setPoint(1, QPoint(refToScreenX(yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth))); yawIndicator.setPoint(2, QPoint(refToScreenX(-yawIndicatorWidth/2.0f), refToScreenY(yawIndicatorY+yawIndicatorWidth))); yawIndicator.setPoint(3, QPoint(refToScreenX(0.0f), refToScreenY(yawIndicatorY))); - painter.setPen(defaultColor); painter.drawPolyline(yawIndicator); + painter.setPen(linePen); // CENTER @@ -752,7 +754,7 @@ void HUD::paintHUD() // __ __ // \/\/ // - const float hIndicatorWidth = 7.0f; + const float hIndicatorWidth = 20.0f; const float hIndicatorY = -25.0f; const float hIndicatorYLow = hIndicatorY + hIndicatorWidth / 6.0f; const float hIndicatorSegmentWidth = hIndicatorWidth / 7.0f; @@ -764,18 +766,15 @@ void HUD::paintHUD() hIndicator.setPoint(4, QPoint(refToScreenX(0.0f+hIndicatorSegmentWidth*1.0f), refToScreenY(hIndicatorYLow))); hIndicator.setPoint(5, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f-hIndicatorSegmentWidth*1.75f), refToScreenY(hIndicatorY))); hIndicator.setPoint(6, QPoint(refToScreenX(0.0f+hIndicatorWidth/2.0f), refToScreenY(hIndicatorY))); - painter.setPen(defaultColor); painter.drawPolyline(hIndicator); // SETPOINT - const float centerWidth = 4.0f; - painter.setPen(defaultColor); - painter.setBrush(Qt::NoBrush); + const float centerWidth = 8.0f; // TODO //painter.drawEllipse(QPointF(refToScreenX(qMin(10.0f, values.value("roll desired", 0.0f) * 10.0f)), refToScreenY(qMin(10.0f, values.value("pitch desired", 0.0f) * 10.0f))), refToScreenX(centerWidth/2.0f), refToScreenX(centerWidth/2.0f)); - const float centerCrossWidth = 10.0f; + const float centerCrossWidth = 20.0f; // left painter.drawLine(QPointF(refToScreenX(-centerWidth / 2.0f), refToScreenY(0.0f)), QPointF(refToScreenX(-centerCrossWidth / 2.0f), refToScreenY(0.0f))); // right @@ -786,12 +785,11 @@ void HUD::paintHUD() // COMPASS - const float compassY = -vheight/2.0f + 10.0f; - QRectF compassRect(QPointF(refToScreenX(-5.0f), refToScreenY(compassY)), QSizeF(refToScreenX(10.0f), refToScreenY(5.0f))); + const float compassY = -vheight/2.0f + 6.0f; + QRectF compassRect(QPointF(refToScreenX(-12.0f), refToScreenY(compassY)), QSizeF(refToScreenX(24.0f), refToScreenY(12.0f))); painter.setBrush(Qt::NoBrush); - painter.setPen(Qt::SolidLine); - painter.setPen(defaultColor); - painter.drawRoundedRect(compassRect, 2, 2); + painter.setPen(linePen); + painter.drawRoundedRect(compassRect, 3, 3); QString yawAngle; // const float yawDeg = ((values.value("yaw", 0.0f)/M_PI)*180.0f)+180.f; @@ -803,13 +801,16 @@ void HUD::paintHUD() /* final safeguard for really stupid systems */ int yawCompass = static_cast(yawDeg) % 360; yawAngle.sprintf("%03d", yawCompass); - paintText(yawAngle, defaultColor, 3.5f, -4.3f, compassY+ 0.97f, &painter); + paintText(yawAngle, defaultColor,8.5f, -9.8f, compassY+ 1.7f, &painter); + + painter.setBrush(Qt::NoBrush); + painter.setPen(linePen); // CHANGE RATE STRIPS - drawChangeRateStrip(-51.0f, -50.0f, 15.0f, -1.0f, 1.0f, -zSpeed, &painter); + drawChangeRateStrip(-65.0f, -60.0f, 25.0f, -10.0f, 10.0f, -zSpeed, &painter); // CHANGE RATE STRIPS - drawChangeRateStrip(49.0f, -50.0f, 15.0f, -1.0f, 1.0f, totalAcc, &painter); + drawChangeRateStrip(65.0f, -60.0f, 25.0f, -10.0f, 10.0f, totalAcc, &painter); // GAUGES @@ -822,10 +823,15 @@ void HUD::paintHUD() gaugeAltitude = -zPos; } - drawChangeIndicatorGauge(-vGaugeSpacing, -15.0f, 10.0f, 2.0f, gaugeAltitude, defaultColor, &painter, false); + painter.setBrush(Qt::NoBrush); + painter.setPen(linePen); + + drawChangeIndicatorGauge(-vGaugeSpacing, 35.0f, 30.0f, 10.0f, gaugeAltitude, defaultColor, &painter, false); + paintText("alt m", defaultColor, 5.5f, -73.0f, 50, &painter); // Right speed gauge - drawChangeIndicatorGauge(vGaugeSpacing, -15.0f, 10.0f, 5.0f, totalSpeed, defaultColor, &painter, false); + drawChangeIndicatorGauge(vGaugeSpacing, 35.0f, 30.0f, 10.0f, totalSpeed, defaultColor, &painter, false); + paintText("v m/s", defaultColor, 5.5f, 55.0f, 50, &painter); // Waypoint name @@ -961,8 +967,8 @@ void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter const float pitchWidth = 30.0f; const float pitchGap = pitchWidth / 2.5f; const float pitchHeight = pitchWidth / 12.0f; - const float textSize = pitchHeight * 1.1f; - const float lineWidth = 0.5f; + const float textSize = pitchHeight * 1.6f; + const float lineWidth = 1.5f; // Positive pitch indicator: // @@ -975,7 +981,7 @@ void HUD::paintPitchLinePos(QString text, float refPosX, float refPosY, QPainter // Left horizontal line drawLine(refPosX-pitchWidth/2.0f, refPosY, refPosX-pitchGap/2.0f, refPosY, lineWidth, defaultColor, painter); // Text left - paintText(text, defaultColor, textSize, refPosX-pitchWidth/2.0 + 0.75f, refPosY + pitchHeight - 1.75f, painter); + paintText(text, defaultColor, textSize, refPosX-pitchWidth/2.0 + 0.75f, refPosY + pitchHeight - 1.3f, painter); // Right vertical line drawLine(refPosX+pitchWidth/2.0f, refPosY, refPosX+pitchWidth/2.0f, refPosY+pitchHeight, lineWidth, defaultColor, painter); @@ -988,10 +994,10 @@ void HUD::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter const float pitchWidth = 30.0f; const float pitchGap = pitchWidth / 2.5f; const float pitchHeight = pitchWidth / 12.0f; - const float textSize = pitchHeight * 1.1f; + const float textSize = pitchHeight * 1.6f; const float segmentWidth = ((pitchWidth - pitchGap)/2.0f) / 7.0f; ///< Four lines and three gaps -> 7 segments - const float lineWidth = 0.1f; + const float lineWidth = 1.5f; // Negative pitch indicator: // @@ -1007,7 +1013,7 @@ void HUD::paintPitchLineNeg(QString text, float refPosX, float refPosY, QPainter drawLine(refPosX-pitchWidth/2.0+(i*segmentWidth), refPosY, refPosX-pitchWidth/2.0+(i*segmentWidth)+segmentWidth, refPosY, lineWidth, defaultColor, painter); } // Text left - paintText(text, defaultColor, textSize, refPosX-pitchWidth/2.0f + 0.75f, refPosY + pitchHeight - 1.75f, painter); + paintText(text, defaultColor, textSize, refPosX-pitchWidth/2.0f + 0.75f, refPosY + pitchHeight - 1.3f, painter); // Right vertical line drawLine(refPosX+pitchGap/2.0, refPosY, refPosX+pitchGap/2.0, refPosY-pitchHeight, lineWidth, defaultColor, painter); @@ -1080,13 +1086,6 @@ void HUD::drawPolygon(QPolygonF refPolygon, QPainter* painter) void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRate, float maxRate, float value, QPainter* painter) { - QBrush brush(defaultColor, Qt::NoBrush); - painter->setBrush(brush); - QPen rectPen(Qt::SolidLine); - rectPen.setWidth(0); - rectPen.setColor(defaultColor); - painter->setPen(rectPen); - float scaledValue = value; // Saturate value @@ -1105,7 +1104,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat // - const float width = height / 8.0f; - const float lineWidth = 0.5f; + const float lineWidth = 1.5f; // Indicator lines // Top horizontal line @@ -1120,7 +1119,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat // Text QString label; label.sprintf("< %+06.2f", value); - paintText(label, defaultColor, 3.0f, xRef+width/2.0f, yRef+height-((scaledValue - minRate)/(maxRate-minRate))*height - 1.6f, painter); + paintText(label, defaultColor, 6.0f, xRef+width/2.0f, yRef+height-((scaledValue - minRate)/(maxRate-minRate))*height - 1.6f, painter); } //void HUD::drawSystemIndicator(float xRef, float yRef, int maxNum, float maxWidth, float maxHeight, QPainter* painter) @@ -1205,17 +1204,19 @@ void HUD::drawChangeIndicatorGauge(float xRef, float yRef, float radius, float e // Draw the circle QPen circlePen(Qt::SolidLine); if (!solid) circlePen.setStyle(Qt::DotLine); - circlePen.setWidth(refLineWidthToPen(0.5f)); circlePen.setColor(defaultColor); + circlePen.setWidth(refLineWidthToPen(2.0f)); painter->setBrush(Qt::NoBrush); painter->setPen(circlePen); - drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.0f, color, painter); + drawCircle(xRef, yRef, radius, 200.0f, 170.0f, 1.5f, color, painter); QString label; label.sprintf("%05.1f", value); + float textSize = radius / 2.5; + // Draw the value - paintText(label, color, 4.5f, xRef-7.5f, yRef-2.0f, painter); + paintText(label, color, textSize, xRef-textSize*1.7f, yRef-textSize*0.4f, painter); // Draw the needle // Scale the rotation so that the gauge does one revolution diff --git a/src/ui/Linechart.ui b/src/ui/Linechart.ui index 0e6b0fd74fd5060af9d355592e604eed7b7c09c6..4a6a23e5ce399224210169f2f170d8d88ce67aa6 100644 --- a/src/ui/Linechart.ui +++ b/src/ui/Linechart.ui @@ -47,7 +47,7 @@ 10 - + 6 @@ -103,8 +103,8 @@ 0 0 - 202 - 488 + 884 + 491 @@ -164,6 +164,28 @@ + + 0 + + + QLayout::SetMinimumSize + + + 0 + + + + + Qt::Vertical + + + + 20 + 0 + + + + diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 573df8a5c6734ded914fefc2f2a6584427a23890..da698e4b6de3c808fabfb068d2f686cd1d505ebe 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -37,6 +37,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include "QGC.h" #include "MAVLinkSimulationLink.h" @@ -643,6 +644,26 @@ void MainWindow::showCentralWidget() centerStack->setCurrentWidget(widget); } +void MainWindow::showHILConfigurationWidget(UASInterface* uas) +{ + // Add simulation configuration widget + UAS* mav = dynamic_cast(uas); + + if (mav) + { + QGCHilConfiguration* hconf = new QGCHilConfiguration(mav, this); + QString hilDockName = tr("HIL Config (%1)").arg(uas->getUASName()); + QDockWidget* hilDock = new QDockWidget(hilDockName, this); + hilDock->setWidget(hconf); + hilDock->setObjectName(QString("HIL_CONFIG_%1").arg(uas->getUASID())); + addTool(hilDock, hilDockName, Qt::RightDockWidgetArea); + + } + + // Reload view state in case new widgets were added + loadViewState(); +} + void MainWindow::closeEvent(QCloseEvent *event) { if (isVisible()) storeViewState(); @@ -1424,19 +1445,6 @@ void MainWindow::UASCreated(UASInterface* uas) if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true); if (!ui.menuUnmanned_System->isEnabled()) ui.menuUnmanned_System->setEnabled(true); - // Add simulation configuration widget - UAS* mav = dynamic_cast(uas); - - if (mav) - { - QGCHilConfiguration* hconf = new QGCHilConfiguration(mav->getHILSimulation(), this); - QString hilDockName = tr("HIL Config (%1)").arg(uas->getUASName()); - QDockWidget* hilDock = new QDockWidget(hilDockName, this); - hilDock->setWidget(hconf); - hilDock->setObjectName(QString("HIL_CONFIG_%1").arg(uas->getUASID())); - addTool(hilDock, hilDockName, Qt::RightDockWidgetArea); - } - // Reload view state in case new widgets were added loadViewState(); } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 828395c1797343d19aee399234e47d2af3953eb0..b5d1f0a40aed8e02ca88545cf812c422d03c9ec1 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -201,6 +201,9 @@ public slots: /** @brief Load custom widgets from default file */ void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType); + /** @brief Loads and shows the HIL Configuration Widget for the given UAS*/ + void showHILConfigurationWidget(UASInterface *uas); + void closeEvent(QCloseEvent* event); /** @brief Load data view, allowing to plot flight data */ diff --git a/src/ui/QGCHilConfiguration.cc b/src/ui/QGCHilConfiguration.cc index 2483ac6a32fcaddc0ad60691ba7a0da0bb9b7a2f..506331dda2f32650ac61c7547ce6421d01080b08 100644 --- a/src/ui/QGCHilConfiguration.cc +++ b/src/ui/QGCHilConfiguration.cc @@ -1,37 +1,15 @@ #include "QGCHilConfiguration.h" #include "ui_QGCHilConfiguration.h" -#include "QGCXPlaneLink.h" -QGCHilConfiguration::QGCHilConfiguration(QGCHilLink* link, QWidget *parent) : +#include "QGCHilFlightGearConfiguration.h" +#include "QGCHilXPlaneConfiguration.h" + +QGCHilConfiguration::QGCHilConfiguration(UAS *mav, QWidget *parent) : QWidget(parent), - link(link), + mav(mav), ui(new Ui::QGCHilConfiguration) { ui->setupUi(this); - - connect(ui->startButton, SIGNAL(clicked(bool)), this, SLOT(toggleSimulation(bool))); - connect(ui->hostComboBox, SIGNAL(activated(QString)), link, SLOT(setRemoteHost(QString))); - connect(link, SIGNAL(remoteChanged(QString)), ui->hostComboBox, SLOT(setEditText(QString))); - connect(link, SIGNAL(statusMessage(QString)), this, SLOT(receiveStatusMessage(QString))); - connect(link, SIGNAL(versionChanged(QString)), ui->simComboBox, SLOT(setEditText(QString))); - connect(ui->simComboBox, SIGNAL(activated(QString)), link, SLOT(setVersion(QString))); - ui->simComboBox->setEditText(link->getVersion()); - - ui->startButton->setText(tr("Connect")); - - QGCXPlaneLink* xplane = dynamic_cast(link); - - if (xplane) - { - connect(ui->randomAttitudeButton, SIGNAL(clicked()), link, SLOT(setRandomAttitude())); - connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition())); - connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(setAirframe(QString))); - ui->airframeComboBox->setCurrentIndex(link->getAirFrameIndex()); - } - - ui->hostComboBox->clear(); - ui->hostComboBox->addItem(link->getRemoteHost()); -// connect(ui->) } void QGCHilConfiguration::receiveStatusMessage(const QString& message) @@ -39,23 +17,29 @@ void QGCHilConfiguration::receiveStatusMessage(const QString& message) ui->statusLabel->setText(message); } -void QGCHilConfiguration::toggleSimulation(bool connect) +QGCHilConfiguration::~QGCHilConfiguration() +{ + delete ui; +} + +void QGCHilConfiguration::on_simComboBox_currentIndexChanged(int index) { - Q_UNUSED(connect); - if (!link->isConnected()) + if(1 == index) { - link->setRemoteHost(ui->hostComboBox->currentText()); - link->connectSimulation(); - ui->startButton->setText(tr("Disconnect")); + // Ensure the sim exists and is disabled + mav->enableHilFlightGear(false, ""); + QGCHilFlightGearConfiguration* hfgconf = new QGCHilFlightGearConfiguration(mav, this); + hfgconf->show(); + ui->simulatorConfigurationDockWidget->setWidget(hfgconf); + } - else + else if(2 == index || 3 == index) { - link->disconnectSimulation(); - ui->startButton->setText(tr("Connect")); - } -} + // Ensure the sim exists and is disabled + mav->enableHilXPlane(false); + QGCHilXPlaneConfiguration* hxpconf = new QGCHilXPlaneConfiguration(mav->getHILSimulation(), this); + hxpconf->show(); + ui->simulatorConfigurationDockWidget->setWidget(hxpconf); -QGCHilConfiguration::~QGCHilConfiguration() -{ - delete ui; + } } diff --git a/src/ui/QGCHilConfiguration.h b/src/ui/QGCHilConfiguration.h index bb9fabfd942e4afa745b5d8d072583f410cdc4c3..14ef7c63fbe583e391df21ae2c847dedf2ef4bb1 100644 --- a/src/ui/QGCHilConfiguration.h +++ b/src/ui/QGCHilConfiguration.h @@ -4,6 +4,7 @@ #include #include "QGCHilLink.h" +#include "UAS.h" namespace Ui { class QGCHilConfiguration; @@ -14,18 +15,19 @@ class QGCHilConfiguration : public QWidget Q_OBJECT public: - QGCHilConfiguration(QGCHilLink* link, QWidget *parent = 0); + QGCHilConfiguration(UAS* mav, QWidget *parent = 0); ~QGCHilConfiguration(); public slots: - /** @brief Start / stop simulation */ - void toggleSimulation(bool connect); /** @brief Receive status message */ void receiveStatusMessage(const QString& message); protected: - QGCHilLink* link; + UAS* mav; +private slots: + void on_simComboBox_currentIndexChanged(int index); + private: Ui::QGCHilConfiguration *ui; }; diff --git a/src/ui/QGCHilConfiguration.ui b/src/ui/QGCHilConfiguration.ui index 04e65c12420902e9f2cb65fbb46687c14687d579..ace3110769acf16b2497c253695458ed782390c0 100644 --- a/src/ui/QGCHilConfiguration.ui +++ b/src/ui/QGCHilConfiguration.ui @@ -7,70 +7,19 @@ 0 0 305 - 261 + 355 + + + 0 + 0 + + Form - - - - - true - - - - X-Plane default - - - - - QRO_X/MK - - - - - QRO_X/Ardrone - - - - - QRO_X/PWM - - - - - Unlimited - - - - - Twinjet - - - - - Early Bird - - - - - Reno Racer - - - - - Slowstick - - - - - Tiny - - - - + @@ -78,96 +27,69 @@ - - - - Set HOME - - - - + Status - - - - Airframe - - - - + true - X-Plane 10 + - X-Plane 9 + Flightgear - - - - - - true - - 127.0.0.1:49000 + X-Plane 10 + + + + + X-Plane 9 - - - - Random POS - - - - - - - Random ATT - - - - - - - Host - - - - - - - Start - - - - - - - Qt::Vertical + + + + + 0 + 0 + - + 20 - 40 + 150 - + + QDockWidget::NoDockWidgetFeatures + + + Simulator Options + + + + + 0 + 0 + + + + diff --git a/src/ui/QGCHilFlightGearConfiguration.cc b/src/ui/QGCHilFlightGearConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..84137ed3eea207ccecc4904c0b490bbc5c177581 --- /dev/null +++ b/src/ui/QGCHilFlightGearConfiguration.cc @@ -0,0 +1,43 @@ +#include "QGCHilFlightGearConfiguration.h" +#include "ui_QGCHilFlightGearConfiguration.h" + +#include "MainWindow.h" + +QGCHilFlightGearConfiguration::QGCHilFlightGearConfiguration(UAS* mav,QWidget *parent) : + QWidget(parent), + mav(mav), + ui(new Ui::QGCHilFlightGearConfiguration) +{ + ui->setupUi(this); + + QStringList items = QStringList(); + if (mav->getSystemType() == MAV_TYPE_FIXED_WING) + { + items << "Rascal110-JSBSim"; + items << "c172p"; + items << "YardStik"; + items << "Malolo1"; + } + else if (mav->getSystemType() == MAV_TYPE_QUADROTOR) + { + items << "arducopter"; + } + else + { + items << ""; + } + ui->aircraftComboBox->addItems(items); +} + +QGCHilFlightGearConfiguration::~QGCHilFlightGearConfiguration() +{ + delete ui; +} + +void QGCHilFlightGearConfiguration::on_startButton_clicked() +{ + //XXX check validity of inputs + QString options = ui->optionsPlainTextEdit->toPlainText(); + options.append(" --aircraft=" + ui->aircraftComboBox->currentText()); + mav->enableHilFlightGear(true, options); +} diff --git a/src/ui/QGCHilFlightGearConfiguration.h b/src/ui/QGCHilFlightGearConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..278e33ac55a0d6ec31390052f24a5c5e95db51c3 --- /dev/null +++ b/src/ui/QGCHilFlightGearConfiguration.h @@ -0,0 +1,32 @@ +#ifndef QGCHILFLIGHTGEARCONFIGURATION_H +#define QGCHILFLIGHTGEARCONFIGURATION_H + +#include + +#include "QGCHilLink.h" +#include "QGCFlightGearLink.h" +#include "UAS.h" + +namespace Ui { +class QGCHilFlightGearConfiguration; +} + +class QGCHilFlightGearConfiguration : public QWidget +{ + Q_OBJECT + +public: + explicit QGCHilFlightGearConfiguration(UAS* mav, QWidget *parent = 0); + ~QGCHilFlightGearConfiguration(); + +protected: + UAS* mav; + +private slots: + void on_startButton_clicked(); + +private: + Ui::QGCHilFlightGearConfiguration *ui; +}; + +#endif // QGCHILFLIGHTGEARCONFIGURATION_H diff --git a/src/ui/QGCHilFlightGearConfiguration.ui b/src/ui/QGCHilFlightGearConfiguration.ui new file mode 100644 index 0000000000000000000000000000000000000000..2495b0784f6acd616f2d14d6bfdf3ace17f07d98 --- /dev/null +++ b/src/ui/QGCHilFlightGearConfiguration.ui @@ -0,0 +1,92 @@ + + + QGCHilFlightGearConfiguration + + + + 0 + 0 + 190 + 246 + + + + + 0 + 0 + + + + Form + + + Qt::LeftToRight + + + false + + + + 0 + + + 6 + + + + + + 0 + 0 + + + + Start + + + + + + + Airframe: + + + + + + + + 0 + 0 + + + + true + + + + + + + <html><head/><body><p>Additional Options:</p></body></html> + + + + + + + + 0 + 0 + + + + --in-air --roll=0 --pitch=0 --vc=90 --heading=300 --timeofday=noon --disable-hud-3d --disable-fullscreen --geometry=400x300 --disable-anti-alias-hud --wind=0@0 --turbulence=0.0 --prop:/sim/frame-rate-throttle-hz=30 --control=mouse --disable-intro-music --disable-sound --disable-random-objects --disable-ai-models --shading-flat --fog-disable --disable-specular-highlight --disable-random-objects --disable-panel --disable-clouds --fdm=jsb --units-meters --notrim --prop:/engines/engine/running=true + + + + + + + + diff --git a/src/ui/QGCHilXPlaneConfiguration.cc b/src/ui/QGCHilXPlaneConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..4914317e5b78bf12e7c932a63d7cd82803bd40ad --- /dev/null +++ b/src/ui/QGCHilXPlaneConfiguration.cc @@ -0,0 +1,57 @@ +#include "QGCHilXPlaneConfiguration.h" +#include "ui_QGCHilXPlaneConfiguration.h" +#include "QGCXPlaneLink.h" + +QGCHilXPlaneConfiguration::QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *parent) : + QWidget(parent), + ui(new Ui::QGCHilXPlaneConfiguration) +{ + ui->setupUi(this); + this->link = link; + + connect(ui->startButton, SIGNAL(clicked(bool)), this, SLOT(toggleSimulation(bool))); + connect(ui->hostComboBox, SIGNAL(activated(QString)), link, SLOT(setRemoteHost(QString))); + connect(link, SIGNAL(remoteChanged(QString)), ui->hostComboBox, SLOT(setEditText(QString))); + connect(link, SIGNAL(statusMessage(QString)), parent, SLOT(receiveStatusMessage(QString))); + +// connect(mav->getHILSimulation(), SIGNAL(statusMessage(QString)), this, SLOT(receiveStatusMessage(QString))); +// connect(ui->simComboBox, SIGNAL(activated(QString)), mav->getHILSimulation(), SLOT(setVersion(QString))); + + ui->startButton->setText(tr("Connect")); + + QGCXPlaneLink* xplane = dynamic_cast(link); + + if (xplane) + { + connect(ui->randomAttitudeButton, SIGNAL(clicked()), link, SLOT(setRandomAttitude())); + connect(ui->randomPositionButton, SIGNAL(clicked()), link, SLOT(setRandomPosition())); + connect(ui->airframeComboBox, SIGNAL(activated(QString)), link, SLOT(selectAirframe(QString))); + ui->airframeComboBox->setCurrentIndex(link->getAirFrameIndex()); + } + + ui->hostComboBox->clear(); + ui->hostComboBox->addItem(link->getRemoteHost()); + + +} + +void QGCHilXPlaneConfiguration::toggleSimulation(bool connect) +{ + Q_UNUSED(connect); + if (!link->isConnected()) + { + link->setRemoteHost(ui->hostComboBox->currentText()); + link->connectSimulation(); + ui->startButton->setText(tr("Disconnect")); + } + else + { + link->disconnectSimulation(); + ui->startButton->setText(tr("Connect")); + } +} + +QGCHilXPlaneConfiguration::~QGCHilXPlaneConfiguration() +{ + delete ui; +} diff --git a/src/ui/QGCHilXPlaneConfiguration.h b/src/ui/QGCHilXPlaneConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..11def7c1e0b4cb5a208fd6a5e377baec8d182121 --- /dev/null +++ b/src/ui/QGCHilXPlaneConfiguration.h @@ -0,0 +1,31 @@ +#ifndef QGCHILXPLANECONFIGURATION_H +#define QGCHILXPLANECONFIGURATION_H + +#include + +#include "QGCHilLink.h" + +namespace Ui { +class QGCHilXPlaneConfiguration; +} + +class QGCHilXPlaneConfiguration : public QWidget +{ + Q_OBJECT + +public: + explicit QGCHilXPlaneConfiguration(QGCHilLink* link, QWidget *parent = 0); + ~QGCHilXPlaneConfiguration(); + +public slots: + /** @brief Start / stop simulation */ + void toggleSimulation(bool connect); + +protected: + QGCHilLink* link; + +private: + Ui::QGCHilXPlaneConfiguration *ui; +}; + +#endif // QGCHILXPLANECONFIGURATION_H diff --git a/src/ui/QGCHilXPlaneConfiguration.ui b/src/ui/QGCHilXPlaneConfiguration.ui new file mode 100644 index 0000000000000000000000000000000000000000..eaf6b2661ed2cac41d92d846c0d73bc8449f6fb4 --- /dev/null +++ b/src/ui/QGCHilXPlaneConfiguration.ui @@ -0,0 +1,148 @@ + + + QGCHilXPlaneConfiguration + + + + 0 + 0 + 243 + 261 + + + + Form + + + + 0 + + + + + Airframe + + + + + + + true + + + + X-Plane default + + + + + QRO_X/MK + + + + + QRO_X/Ardrone + + + + + QRO_X/PWM + + + + + Unlimited + + + + + Twinjet + + + + + Early Bird + + + + + Reno Racer + + + + + Slowstick + + + + + Tiny + + + + + + + + Set HOME + + + + + + + true + + + + 127.0.0.1:49000 + + + + + + + + Random POS + + + + + + + Random ATT + + + + + + + Host + + + + + + + Start + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h index 013c81335a40aeec27d9e9d3778ad21bfac2c5b9..8dc801e5778d77ed768abed00736714ae098fb7f 100644 --- a/src/ui/QGCParamWidget.h +++ b/src/ui/QGCParamWidget.h @@ -57,7 +57,7 @@ public: double getParamMin(const QString& param) { return paramMin.value(param, 0.0f); } double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); } double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); } - const QString& getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } + QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); } signals: /** @brief A parameter was changed in the widget, NOT onboard */ diff --git a/src/ui/QGCToolBar.cc b/src/ui/QGCToolBar.cc index 2b49cbc6fe0b9847d02fc49cafd472fed28468ce..888a48923d6d4f21729ed6baddb291b4cac2bb1e 100644 --- a/src/ui/QGCToolBar.cc +++ b/src/ui/QGCToolBar.cc @@ -54,7 +54,7 @@ QGCToolBar::QGCToolBar(QWidget *parent) : // Add internal actions // Add MAV widget symbolButton = new QToolButton(this); - symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 0px 0px 20px; background-color: none; }"); + symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; }"); addWidget(symbolButton); toolBarNameLabel = new QLabel("------", this); @@ -226,39 +226,6 @@ void QGCToolBar::logging(bool checked) void QGCToolBar::addPerspectiveChangeAction(QAction* action) { insertAction(toggleLoggingAction, action); - - // Set tab style - QWidget* widget = widgetForAction(action); - widget->setStyleSheet("\ - * { font-weight: bold; min-height: 16px; min-width: 24px; \ - border-top: 1px solid #BBBBBB; \ - border-bottom: 0px; \ - border-left: 1px solid #BBBBBB; \ - border-right: 1px solid #BBBBBB; \ - border-top-left-radius: 5px; \ - border-top-right-radius: 5px; \ - border-bottom-left-radius: 0px; \ - border-bottom-right-radius: 0px; \ - max-height: 22px; \ - margin-top: 4px; \ - margin-left: 2px; \ - margin-bottom: 0px; \ - margin-right: 2px; \ - background-color: #222222; \ - } \ - *:checked { \ - background-color: #000000; \ - border-top: 2px solid #379AC3; \ - border-bottom: 0px; \ - border-left: 2px solid #379AC3; \ - border-right: 2px solid #379AC3; \ - } \ - *:pressed { \ - background-color: qlineargradient(x1: 0, y1: 0, x2: 0, y2: 1, stop: 0 #bbbbbb, stop: 1 #b0b0b0); \ - border-top: 2px solid #379AC3; \ - border-bottom: 0px; \ - border-left: 2px solid #379AC3; \ - border-right: 2px solid #379AC3; }"); } void QGCToolBar::setActiveUAS(UASInterface* active) @@ -322,6 +289,8 @@ void QGCToolBar::updateArmingState(bool armed) { systemArmed = armed; changed = true; + /* important, immediately update */ + updateView(); } void QGCToolBar::updateView() @@ -377,6 +346,8 @@ void QGCToolBar::updateState(UASInterface* system, QString name, QString descrip Q_UNUSED(description); if (state != name) changed = true; state = name; + /* important, immediately update */ + updateView(); } void QGCToolBar::updateMode(int system, QString name, QString description) @@ -385,11 +356,16 @@ void QGCToolBar::updateMode(int system, QString name, QString description) Q_UNUSED(description); if (mode != name) changed = true; mode = name; + /* important, immediately update */ + updateView(); } void QGCToolBar::updateName(const QString& name) { - if (systemName != name) changed = true; + if (systemName != name) + { + changed = true; + } systemName = name; } diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index c0f08fa90bd68cb8800c7a794038d52813f62fd4..d38095a5cd1bf425f0fd9ea83746e498ec8689dc 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -191,10 +191,10 @@ void QGCVehicleConfig::writeCalibrationRC() for (unsigned int i = 0; i < chanMax; ++i) { - mav->setParameter(0, minTpl.arg(i), rcMin[i]); - mav->setParameter(0, trimTpl.arg(i), rcTrim[i]); - mav->setParameter(0, maxTpl.arg(i), rcMax[i]); - mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1); + mav->setParameter(0, minTpl.arg(i+1), rcMin[i]); + mav->setParameter(0, trimTpl.arg(i+1), rcTrim[i]); + mav->setParameter(0, maxTpl.arg(i+1), rcMax[i]); + mav->setParameter(0, revTpl.arg(i+1), (rcRev[i]) ? -1 : 1); } // Write mappings @@ -222,13 +222,13 @@ void QGCVehicleConfig::requestCalibrationRC() for (unsigned int i = 0; i < chanMax; ++i) { - mav->requestParameter(0, minTpl.arg(i)); + mav->requestParameter(0, minTpl.arg(i+1)); QGC::SLEEP::usleep(5000); - mav->requestParameter(0, trimTpl.arg(i)); + mav->requestParameter(0, trimTpl.arg(i+1)); QGC::SLEEP::usleep(5000); - mav->requestParameter(0, maxTpl.arg(i)); + mav->requestParameter(0, maxTpl.arg(i+1)); QGC::SLEEP::usleep(5000); - mav->requestParameter(0, revTpl.arg(i)); + mav->requestParameter(0, revTpl.arg(i+1)); QGC::SLEEP::usleep(5000); } } @@ -379,7 +379,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (minTpl.exactMatch(parameterName)) { bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok); + unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; if (ok && (index > 0) && (index < chanMax)) { rcMin[index] = value.toInt(); @@ -388,7 +388,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (maxTpl.exactMatch(parameterName)) { bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok); + unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; if (ok && (index > 0) && (index < chanMax)) { rcMax[index] = value.toInt(); @@ -397,7 +397,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (trimTpl.exactMatch(parameterName)) { bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok); + unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; if (ok && (index > 0) && (index < chanMax)) { rcTrim[index] = value.toInt(); @@ -406,7 +406,7 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete if (revTpl.exactMatch(parameterName)) { bool ok; - unsigned int index = parameterName.mid(2, 1).toInt(&ok); + unsigned int index = parameterName.mid(2, 1).toInt(&ok) - 1; if (ok && (index > 0) && (index < chanMax)) { rcRev[index] = (value.toInt() == -1) ? true : false; diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui index 27f505cf2198b04ec18180f1c45b734200028fa6..89628d17c569e0e88ed2de2738524dd4bf33e019 100644 --- a/src/ui/QGCVehicleConfig.ui +++ b/src/ui/QGCVehicleConfig.ui @@ -40,13 +40,16 @@ - 2 + 1 RC Calibration + + 20 + @@ -716,10 +719,26 @@ Sensor Calibration + + 20 + - + + + + Qt::Vertical + + + + 20 + 40 + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> @@ -732,7 +751,7 @@ p, li { white-space: pre-wrap; } <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt;">Magnetometer Calibration</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">Carefully follow the instructions. Click on MAG to start the calibration. Watch the communication console for further instructions (Available through Main Menu -&gt; Tool Widgets -&gt; Communication Console). Do not calibrate the vehicle in vincinity of metal, e.g. from a table or chair. Start the calibration, leave the system unmoved on the table. Wait for the double beep. Next move the system in a figure eight, roll and pitch it strongly and perform the figure eight also upside-down. The calibration is finished after the triple beep.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt;">Carefully follow the instructions. Click on MAG to start the calibration. Watch the communication console for further instructions (Available through Main Menu -&gt; Tool Widgets -&gt; Communication Console). Do not calibrate the vehicle in vincinity of metal, e.g. from a table or chair. Start the calibration, leave the system unmoved on the table. Wait for the double beep. Next move the system in a figure eight, roll and pitch it strongly, rotate around all axes and perform the figure eight also upside-down. The calibration is finished after the triple beep.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt;"><br /></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:16pt;">Accelerometer Calibration</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:16pt;"><br /></p> @@ -746,71 +765,106 @@ p, li { white-space: pre-wrap; } - + Multirotor Control - - - - - + + + 20 + + Load Platform Defaults - - - - - - - Position + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + Position + + + + 0 + + + + + true - - - - - + + + + 0 + 0 + 651 + 203 + + + + + 0 + + + + + + - - - - Attitude + + + + + + + Attitude + + + + 0 + + + + + true - - - 0 + + + + 0 + 0 + 651 + 204 + - - - - true - - - - - 0 - 0 - 541 - 417 - - - - - 0 - - - - - - - - - + + + 0 + + + + + + @@ -822,37 +876,103 @@ p, li { white-space: pre-wrap; } Fixed Wing Control - - - + + + 20 + + + - Attitude + Position - + + + 0 + - + + + true + + + + + 0 + 0 + 651 + 203 + + + + + 0 + + + + + + + - + - + Load Platform Defaults - - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + - Position + Attitude - + + + 0 + - + + + true + + + + + 0 + 0 + 651 + 204 + + + + + 0 + + + + + + + diff --git a/src/ui/RadioCalibration/RadioCalibrationWindow.h b/src/ui/RadioCalibration/RadioCalibrationWindow.h index 855540132b97aeb115e709c0b4ddd18ee23117c8..536a4993c1e211553915fdacb9437b3255923c6e 100644 --- a/src/ui/RadioCalibration/RadioCalibrationWindow.h +++ b/src/ui/RadioCalibration/RadioCalibrationWindow.h @@ -50,8 +50,6 @@ This file is part of the QGROUNDCONTROL project #include "SwitchCalibrator.h" #include "CurveCalibrator.h" -#include "../../../mavlink/include/mavlink/v1.0/common/mavlink.h" -#include "../../../mavlink/include/mavlink/v1.0/mavlink_types.h" #include "UAS.h" #include "UASManager.h" #include "RadioCalibrationData.h" diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index 93502e6da308860372ae9d078d4a4002008e6273..3970e1562b980382e973e4bff2d3c1fa563434b0 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -2,6 +2,7 @@ #include #include #include +#include #include "QGCParamSlider.h" #include "ui_QGCParamSlider.h" @@ -53,7 +54,8 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) : connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter())); connect(ui->editRefreshParamsButton, SIGNAL(clicked()), this, SLOT(refreshParamList())); connect(ui->editInfoCheckBox, SIGNAL(clicked(bool)), this, SLOT(showInfo(bool))); - + // connect to self + connect(ui->infoLabel, SIGNAL(released()), this, SLOT(showTooltip())); // Set the current UAS if present connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); } @@ -63,6 +65,17 @@ QGCParamSlider::~QGCParamSlider() delete ui; } +void QGCParamSlider::showTooltip() +{ + QWidget* sender = dynamic_cast(QObject::sender()); + + if (sender) + { + QPoint point = mapToGlobal(pos()); + QToolTip::showText(point, sender->toolTip()); + } +} + void QGCParamSlider::refreshParamList() { ui->editSelectParamComboBox->setEnabled(true); @@ -70,6 +83,7 @@ void QGCParamSlider::refreshParamList() if (uas) { uas->getParamManager()->requestParameterList(); + ui->editStatusLabel->setText(tr("Parameter list updating..")); } } @@ -89,7 +103,7 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas) requestParameter(); // Set param info QString text = uas->getParamManager()->getParamInfo(parameterName); - ui->infoLabel->setText(text); + ui->infoLabel->setToolTip(text); // Force-uncheck and hide label if no description is available if (ui->editInfoCheckBox->isChecked()) { @@ -345,6 +359,11 @@ void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, i } ui->valueSlider->setValue(floatToScaledInt(value.toDouble())); } + + if (paramIndex == paramCount - 1) + { + ui->editStatusLabel->setText(tr("Complete parameter list received.")); + } } void QGCParamSlider::changeEvent(QEvent *e) diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h index d12d9f4f0cbbf74cb1f4f311ad03854f4cb7715d..38f21e6e16c350da7f29393655c196ba10183013 100644 --- a/src/ui/designer/QGCParamSlider.h +++ b/src/ui/designer/QGCParamSlider.h @@ -41,6 +41,8 @@ public slots: void setParamValue(int value); /** @brief Show descriptive text next to slider */ void showInfo(bool enable); + /** @brief Show tool tip of calling element */ + void showTooltip(); protected slots: /** @brief Request the parameter of this widget from the MAV */ diff --git a/src/ui/designer/QGCParamSlider.ui b/src/ui/designer/QGCParamSlider.ui index ff26c4011a25896eb836fb3e2abe5681a7c445bf..ed911775491303530e740c2204991c7ae55fe636 100644 --- a/src/ui/designer/QGCParamSlider.ui +++ b/src/ui/designer/QGCParamSlider.ui @@ -13,7 +13,7 @@ Form - + 6 @@ -32,7 +32,7 @@ 12 - + -999999999 @@ -42,7 +42,7 @@ - + false @@ -55,39 +55,68 @@ - - + + + + + 0 + 0 + + + + Qt::Horizontal + + + + + 60 0 - - Name + + + 250 + 16777215 + - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + 1000000 + + + Qt::Horizontal - - - - MIN: + + + + Done - - -999999999.000000000000000 + + + + + + + 0 + 0 + - - 999999999.000000000000000 + + Qt::Horizontal - - + + - <Parameter Name / Label> + Show Info + + + true @@ -104,77 +133,49 @@ - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Transmit the current slider value to the system - - - Transmit the current slider value to the system + + + + true - W + Refresh - - - + + + + Qt::Vertical + + - 0 - 0 + 20 + 40 - - Qt::Horizontal - - + - - + + - 60 + 0 0 - - - 250 - 16777215 - - - - 1000000 + + Read the current parameter value on the system - - Qt::Horizontal + + Read the current parameter value on the system - - - - - Show Info - - - true + R - + false @@ -187,36 +188,59 @@ + + + + <Parameter Name / Label> + + + + + + + Please click first on refresh to update selection menus.. + + + - + 0 0 + + + 16777215 + 16777215 + + - Read the current parameter value on the system + Transmit the current slider value to the system - Read the current parameter value on the system + Transmit the current slider value to the system - R + W - - - - Please click first on refresh to update selection menus.. + + + + -999999999.000000000000000 + + + 999999999.000000000000000 - - + + - MAX: + MIN: -999999999.000000000000000 @@ -226,8 +250,11 @@ - - + + + + MAX: + -999999999.000000000000000 @@ -236,54 +263,37 @@ - - - - - + + - 0 + 60 0 - - Qt::Horizontal - - - - - - - true - - Refresh + Name - - - - - - Done + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - Qt::Vertical + + + + - - - 20 - 40 - + + + :/files/images/status/dialog-information.svg:/files/images/status/dialog-information.svg - + - + + + diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc index f1429795cf3463773d002807299c051ed0cd5d70..7d3acabb5f0eea97779cf83f9c55d2d2d667db3e 100644 --- a/src/ui/uas/UASView.cc +++ b/src/ui/uas/UASView.cc @@ -40,6 +40,7 @@ This file is part of the PIXHAWK project #include "UASWaypointManager.h" #include "MainWindow.h" #include "ui_UASView.h" +#include UASView::UASView(UASInterface* uas, QWidget *parent) : QWidget(parent), @@ -68,8 +69,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : removeAction(new QAction("Delete this system", this)), renameAction(new QAction("Rename..", this)), selectAction(new QAction("Control this system", this )), - hilAction(new QAction("Enable Flightgear Hardware-in-the-Loop Simulation", this )), - hilXAction(new QAction("Enable X-Plane Hardware-in-the-Loop Simulation", this )), + hilAction(new QAction("HIL - Hardware in the Loop", this )), selectAirframeAction(new QAction("Choose Airframe", this)), setBatterySpecsAction(new QAction("Set Battery Options", this)), lowPowerModeEnabled(true), @@ -81,9 +81,6 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : lowPowerModeEnabled = MainWindow::instance()->lowPowerModeEnabled(); hilAction->setCheckable(true); - // Flightgear is not ready for prime time - //hilAction->setEnabled(false); - hilXAction->setCheckable(true); m_ui->setupUi(this); @@ -122,8 +119,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : connect(removeAction, SIGNAL(triggered()), this, SLOT(deleteLater())); connect(renameAction, SIGNAL(triggered()), this, SLOT(rename())); connect(selectAction, SIGNAL(triggered()), uas, SLOT(setSelected())); - connect(hilAction, SIGNAL(triggered(bool)), uas, SLOT(enableHilFlightGear(bool))); - connect(hilXAction, SIGNAL(triggered(bool)), uas, SLOT(enableHilXPlane(bool))); + connect(hilAction, SIGNAL(triggered(bool)), this, SLOT(showHILUi())); connect(selectAirframeAction, SIGNAL(triggered()), this, SLOT(selectAirframe())); connect(setBatterySpecsAction, SIGNAL(triggered()), this, SLOT(setBatterySpecs())); connect(uas, SIGNAL(systemRemoved()), this, SLOT(deleteLater())); @@ -504,8 +500,6 @@ void UASView::contextMenuEvent (QContextMenuEvent* event) menu.addAction(removeAction); } menu.addAction(hilAction); - menu.addAction(hilXAction); - // XXX Re-enable later menu.addAction(hilXAction); menu.addAction(selectAirframeAction); menu.addAction(setBatterySpecsAction); menu.exec(event->globalPos()); @@ -566,6 +560,11 @@ void UASView::selectAirframe() } } +void UASView::showHILUi() +{ + MainWindow::instance()->showHILConfigurationWidget(uas); +} + void UASView::refresh() { //setUpdatesEnabled(false); diff --git a/src/ui/uas/UASView.h b/src/ui/uas/UASView.h index 4f249178bb6477f7784340fae81a69960162fa6c..073bebdeecb0a30cb0e49ecd52d0504ca7fb36ec 100644 --- a/src/ui/uas/UASView.h +++ b/src/ui/uas/UASView.h @@ -64,6 +64,7 @@ public slots: void updateMode(int sysId, QString status, QString description); void updateLoad(UASInterface* uas, double load); //void receiveValue(int uasid, QString id, double value, quint64 time); + void showHILUi(); void refresh(); /** @brief Receive new waypoint information */ void setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current);