From 36b4938c093c47e742fa4c404f25a21b4a3e053f Mon Sep 17 00:00:00 2001
From: LM <lm@student.ethz.ch>
Date: Tue, 20 Sep 2011 11:03:56 +0200
Subject: [PATCH] Fixed roll angle in Google earth, still not smooth. Fixed a
 number of threading issues. Fixed all custom widget related bugs. Improved
 MAVLink decoder. Reduced CPU usage substantially across all views

---
 images/earth.html                   |  14 ++--
 src/comm/MAVLinkProtocol.cc         |  11 +---
 src/comm/MAVLinkProtocol.h          |   1 -
 src/comm/ProtocolInterface.h        |   2 +-
 src/uas/UAS.cc                      |  26 +++++---
 src/uas/UAS.h                       |   4 +-
 src/uas/UASManager.cc               |  11 ----
 src/uas/UASManager.h                |   3 +-
 src/ui/HDDisplay.cc                 |  14 ++--
 src/ui/HDDisplay.h                  |   5 +-
 src/ui/HSIDisplay.cc                |   1 +
 src/ui/HSIDisplay.h                 |   1 +
 src/ui/MAVLinkDecoder.cc            |   7 +-
 src/ui/MAVLinkDecoder.h             |   1 +
 src/ui/MainWindow.cc                |   7 +-
 src/ui/QGCParamWidget.cc            |   3 +-
 src/ui/QGCParamWidget.h             |   4 +-
 src/ui/QGCToolBar.cc                |   3 +-
 src/ui/designer/QGCCommandButton.cc |   7 +-
 src/ui/designer/QGCParamSlider.cc   | 128 +++++++++++++++++++++++++++++-------
 src/ui/designer/QGCParamSlider.h    |   7 +-
 src/ui/designer/QGCParamSlider.ui   |  14 +++-
 src/ui/designer/QGCToolWidget.cc    |  20 ++++--
 src/ui/designer/QGCToolWidget.h     |   2 +
 src/ui/map3D/QGCGoogleEarthView.cc  |  39 ++++++-----
 src/ui/uas/UASView.cc               |   4 +-
 26 files changed, 234 insertions(+), 105 deletions(-)

diff --git a/images/earth.html b/images/earth.html
index 363e97d..7666c68 100644
--- a/images/earth.html
+++ b/images/earth.html
@@ -683,11 +683,17 @@ function updateFollowAircraft()
 	
 	if (viewMode != 3) // VIEW_MODE_CHASE_FREE
 	{
-		currView.setTilt(currFollowTilt);
-		currView.setHeading(currFollowHeading);
+		ge.getView().setAbstractView(currView);
+		var camera = ge.getView().copyAsCamera(ge.ALTITUDE_ABSOLUTE);
+		camera.setTilt(currFollowTilt);
+		camera.setRoll(0);
+		camera.setHeading(currFollowHeading);
+		ge.getView().setAbstractView(camera);
+	}
+	else
+	{
+		ge.getView().setAbstractView(currView);
 	}
-	
-	ge.getView().setAbstractView(currView);
 }
 
 function failureCallback(object)
diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc
index c975182..f970c49 100644
--- a/src/comm/MAVLinkProtocol.cc
+++ b/src/comm/MAVLinkProtocol.cc
@@ -147,13 +147,6 @@ MAVLinkProtocol::~MAVLinkProtocol()
     }
 }
 
-
-
-void MAVLinkProtocol::run()
-{
-    exec();
-}
-
 QString MAVLinkProtocol::getLogfileName()
 {
     if (m_logfile) {
@@ -173,7 +166,7 @@ QString MAVLinkProtocol::getLogfileName()
  **/
 void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
 {
-    receiveMutex.lock();
+//    receiveMutex.lock();
     mavlink_message_t message;
     mavlink_status_t status;
     for (int position = 0; position < b.size(); position++) {
@@ -330,7 +323,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
             }
         }
     }
-    receiveMutex.unlock();
+//    receiveMutex.unlock();
 }
 
 /**
diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h
index b074985..57e80c8 100644
--- a/src/comm/MAVLinkProtocol.h
+++ b/src/comm/MAVLinkProtocol.h
@@ -57,7 +57,6 @@ public:
     MAVLinkProtocol();
     ~MAVLinkProtocol();
 
-    void run();
     /** @brief Get the human-friendly name of this protocol */
     QString getName();
     /** @brief Get the system id of this application */
diff --git a/src/comm/ProtocolInterface.h b/src/comm/ProtocolInterface.h
index 070c675..6f0e583 100644
--- a/src/comm/ProtocolInterface.h
+++ b/src/comm/ProtocolInterface.h
@@ -46,7 +46,7 @@ This file is part of the PIXHAWK project
  * @see LinkManager.
  *
  **/
-class ProtocolInterface : public QThread
+class ProtocolInterface : public QObject
 {
     Q_OBJECT
 public:
diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc
index 5429ae6..3979f71 100644
--- a/src/uas/UAS.cc
+++ b/src/uas/UAS.cc
@@ -1733,6 +1733,20 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
     }
 }
 
+void UAS::requestParameter(int component, int id)
+{
+    // Request parameter, use parameter name to request it
+    mavlink_message_t msg;
+    mavlink_param_request_read_t read;
+    read.param_index = id;
+    read.param_id[0] = '\0'; // Enforce null termination
+    read.target_system = uasId;
+    read.target_component = component;
+    mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
+    sendMessage(msg);
+    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
+}
+
 void UAS::requestParameter(int component, const QString& parameter)
 {
     // Request parameter, use parameter name to request it
@@ -1750,7 +1764,7 @@ void UAS::requestParameter(int component, const QString& parameter)
     read.target_component = component;
     mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
     sendMessage(msg);
-    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << parameter;
+    qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM NAME" << parameter;
 }
 
 void UAS::setSystemType(int systemType)
@@ -1840,13 +1854,9 @@ void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float
  **/
 void UAS::launch()
 {
-    // FIXME MAVLINKV10PORTINGNEEDED
-//    mavlink_message_t msg;
-//    // TODO Replace MG System ID with static function call and allow to change ID in GUI
-//    mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_TAKEOFF);
-//    // Send message twice to increase chance of reception
-//    sendMessage(msg);
-//    sendMessage(msg);
+    mavlink_message_t msg;
+    mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), 0, MAV_CMD_NAV_TAKEOFF, 1, 0, 0, 0, 0);
+    sendMessage(msg);
 }
 
 /**
diff --git a/src/uas/UAS.h b/src/uas/UAS.h
index e9b0823..ad263b8 100644
--- a/src/uas/UAS.h
+++ b/src/uas/UAS.h
@@ -465,8 +465,10 @@ public slots:
     /** @brief Request all parameters */
     void requestParameters();
 
-    /** @brief Request a single parameter by index */
+    /** @brief Request a single parameter by name */
     void requestParameter(int component, const QString& parameter);
+    /** @brief Request a single parameter by index */
+    void requestParameter(int component, int id);
 
     /** @brief Set a system parameter */
     void setParameter(const int component, const QString& id, const QVariant& value);
diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc
index 64a83a4..36b4eea 100644
--- a/src/uas/UASManager.cc
+++ b/src/uas/UASManager.cc
@@ -216,7 +216,6 @@ UASManager::UASManager() :
         homeLon(8.549444),
         homeAlt(470.0)
 {
-    start(QThread::LowPriority);
     loadSettings();
     setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);
 }
@@ -230,16 +229,6 @@ UASManager::~UASManager()
     }
 }
 
-
-void UASManager::run()
-{
-    //    forever
-    //    {
-    //        QGC::SLEEP::msleep(5000);
-    //    }
-    exec();
-}
-
 void UASManager::addUAS(UASInterface* uas)
 {
     // WARNING: The active uas is set here
diff --git a/src/uas/UASManager.h b/src/uas/UASManager.h
index c197327..6407e83 100644
--- a/src/uas/UASManager.h
+++ b/src/uas/UASManager.h
@@ -44,7 +44,7 @@ This file is part of the QGROUNDCONTROL project
  * This class keeps a list of all connected / configured UASs. It also stores which
  * UAS is currently select with respect to user input or manual controls.
  **/
-class UASManager : public QThread
+class UASManager : public QObject
 {
     Q_OBJECT
 
@@ -52,7 +52,6 @@ public:
     static UASManager* instance();
     ~UASManager();
 
-    void run();
     /**
      * @brief Get the currently selected UAS
      *
diff --git a/src/ui/HDDisplay.cc b/src/ui/HDDisplay.cc
index 8ee4b3c..c786af6 100644
--- a/src/ui/HDDisplay.cc
+++ b/src/ui/HDDisplay.cc
@@ -50,7 +50,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
     acceptUnitList(new QStringList()),
     lastPaintTime(0),
     columns(3),
-    m_ui(new Ui::HDDisplay)
+    valuesChanged(true)/*,
+    m_ui(new Ui::HDDisplay)*/
 {
     setWindowTitle(title);
     //m_ui->setupUi(this);
@@ -65,9 +66,6 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
     }
 
     restoreState();
-
-    // Set minimum size
-    setMinimumSize(60, 60);
     // Set preferred size
     setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
 
@@ -109,6 +107,7 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
     //    setCursor(Qt::OpenHandCursor);
 
 
+    // Set minimum size
     this->setMinimumHeight(125);
     this->setMinimumWidth(100);
 
@@ -231,6 +230,8 @@ void HDDisplay::restoreState()
     QSettings settings;
     settings.sync();
 
+    acceptList->clear();
+
     QStringList instruments = settings.value(windowTitle()+"_gauges").toString().split('|');
     for (int i = 0; i < instruments.count(); i++) {
         addGauge(instruments.at(i));
@@ -385,6 +386,8 @@ void HDDisplay::setTitle()
 
 void HDDisplay::renderOverlay()
 {
+    if (!valuesChanged || !isVisible()) return;
+
 #if (QGC_EVENTLOOP_DEBUG)
     qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
 #endif
@@ -666,7 +669,7 @@ void HDDisplay::drawSystemIndicator(float xRef, float yRef, int maxNum, float ma
         //   x speed: 2.54
 
         // One column per value
-        QMapIterator<QString, float> value(values);
+        QMapIterator<QString, double> value(values);
 
         float x = xRef;
         float y = yRef;
@@ -820,6 +823,7 @@ void HDDisplay::updateValue(const int uasId, const QString& name, const QString&
     valuesMean.insert(name, (oldMean * meanCount +  value) / (meanCount + 1));
     valuesCount.insert(name, meanCount + 1);
     valuesDot.insert(name, (value - values.value(name, 0.0f)) / ((msec - lastUpdate.value(name, 0))/1000.0f));
+    if (values.value(name, 0.0) != value) valuesChanged = true;
     values.insert(name, value);
     units.insert(name, unit);
     lastUpdate.insert(name, msec);
diff --git a/src/ui/HDDisplay.h b/src/ui/HDDisplay.h
index 4c2c430..15a2240 100644
--- a/src/ui/HDDisplay.h
+++ b/src/ui/HDDisplay.h
@@ -139,7 +139,7 @@ protected:
 //     virtual void resizeEvent(QResizeEvent* event);
 
     UASInterface* uas;                 ///< The uas currently monitored
-    QMap<QString, float> values;       ///< The variables this HUD displays
+    QMap<QString, double> values;       ///< The variables this HUD displays
     QMap<QString, QString> units;      ///< The units
     QMap<QString, float> valuesDot;    ///< First derivative of the variable
     QMap<QString, float> valuesMean;   ///< Mean since system startup for this variable
@@ -172,7 +172,7 @@ protected:
     int warningBlinkRate;      ///< Blink rate of warning messages, will be rounded to the refresh rate
 
     QTimer* refreshTimer;      ///< The main timer, controls the update rate
-    static const int updateInterval = 120; ///< Update interval in milliseconds
+    static const int updateInterval = 300; ///< Update interval in milliseconds
     QPainter* hudPainter;
     QFont font;                ///< The HUD font, per default the free Bitstream Vera SANS, which is very close to actual HUD fonts
     QFontDatabase fontDatabase;///< Font database, only used to load the TrueType font file (the HUD font is directly loaded from file rather than from the system)
@@ -191,6 +191,7 @@ protected:
     QAction* addGaugeAction;   ///< Action adding a gauge
     QAction* setTitleAction;   ///< Action setting the title
     QAction* setColumnsAction; ///< Action setting the number of columns
+    bool valuesChanged;
 
 private:
     Ui::HDDisplay *m_ui;
diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc
index d397b51..ad6907e 100644
--- a/src/ui/HSIDisplay.cc
+++ b/src/ui/HSIDisplay.cc
@@ -179,6 +179,7 @@ void HSIDisplay::paintEvent(QPaintEvent * event)
 
 void HSIDisplay::renderOverlay()
 {
+    if (!isVisible()) return;
 #if (QGC_EVENTLOOP_DEBUG)
     qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
 #endif
diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h
index 82ab782..320b577 100644
--- a/src/ui/HSIDisplay.h
+++ b/src/ui/HSIDisplay.h
@@ -79,6 +79,7 @@ public slots:
     /** @brief Ultrasound/Infrared localization changed */
     void updateInfraredUltrasoundLocalization(UASInterface* uas, int fix);
 
+    /** @brief Repaint the widget */
     void paintEvent(QPaintEvent * event);
     /** @brief Update state from joystick */
     void updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat);
diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc
index 57fa865..51862e7 100644
--- a/src/ui/MAVLinkDecoder.cc
+++ b/src/ui/MAVLinkDecoder.cc
@@ -21,6 +21,11 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
     messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false);
     messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false);
 
+    textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false);
+    textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false);
+    textMessageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, false);
+    textMessageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_INT, false);
+
     connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
 }
 
@@ -81,7 +86,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
             // Enforce null termination
             str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0';
             QString string(name + ": " + str);
-            emit textMessageReceived(msg->sysid, msg->compid, 0, string);
+            if (!textMessageFilter.contains(msgid)) emit textMessageReceived(msg->sysid, msg->compid, 0, string);
         }
         else
         {
diff --git a/src/ui/MAVLinkDecoder.h b/src/ui/MAVLinkDecoder.h
index 4e55eb4..54f9894 100644
--- a/src/ui/MAVLinkDecoder.h
+++ b/src/ui/MAVLinkDecoder.h
@@ -29,6 +29,7 @@ protected:
     mavlink_message_t receivedMessages[256]; ///< Available / known messages
     mavlink_message_info_t messageInfo[256]; ///< Message information
     QMap<uint16_t, bool> messageFilter;               ///< Message/field names not to emit
+    QMap<uint16_t, bool> textMessageFilter;           ///< Message/field names not to emit in text mode
 
 };
 
diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc
index 124b0e1..72b3161 100644
--- a/src/ui/MainWindow.cc
+++ b/src/ui/MainWindow.cc
@@ -1249,11 +1249,8 @@ void MainWindow::UASCreated(UASInterface* uas)
 
     if (!ui.menuConnected_Systems->isEnabled()) ui.menuConnected_Systems->setEnabled(true);
 
-//    // Restore the mainwindow size
-//    if (settings.contains(getWindowGeometryKey()))
-//    {
-//        restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
-//    }
+    // Reload view state in case new widgets were added
+    loadViewState();
 }
 
 /**
diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc
index 4b02cdb..997d63d 100644
--- a/src/ui/QGCParamWidget.cc
+++ b/src/ui/QGCParamWidget.cc
@@ -131,6 +131,7 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
     connect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(addParameter(int,int,int,int,QString,QVariant)));
 
     // Connect retransmission guard
+    connect(this, SIGNAL(requestParameter(int,QString)), uas, SLOT(requestParameter(int,QString)));
     connect(this, SIGNAL(requestParameter(int,int)), uas, SLOT(requestParameter(int,int)));
     connect(&retransmissionTimer, SIGNAL(timeout()), this, SLOT(retransmissionGuardTick()));
 }
@@ -474,7 +475,7 @@ void QGCParamWidget::addParameter(int uas, int component, QString parameterName,
 //            componentName = tr("Component #").arg(component);
 //            break;
 //        }
-        QString componentName = tr("Component #").arg(component);
+        QString componentName = tr("Component #%1").arg(component);
         addComponent(uas, component, componentName);
     }
 
diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h
index 3d9bcf6..13c2009 100644
--- a/src/ui/QGCParamWidget.h
+++ b/src/ui/QGCParamWidget.h
@@ -53,8 +53,10 @@ public:
 signals:
     /** @brief A parameter was changed in the widget, NOT onboard */
     void parameterChanged(int component, QString parametername, QVariant value);
-    /** @brief Request a single parameter */
+    /** @brief Request a single parameter by index */
     void requestParameter(int component, int parameter);
+    /** @brief Request a single parameter by name */
+    void requestParameter(int component, const QString& parameter);
 public slots:
     /** @brief Add a component to the list */
     void addComponent(int uas, int component, QString componentName);
diff --git a/src/ui/QGCToolBar.cc b/src/ui/QGCToolBar.cc
index f9641ab..7797526 100644
--- a/src/ui/QGCToolBar.cc
+++ b/src/ui/QGCToolBar.cc
@@ -214,7 +214,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
         disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
         if (mav->getWaypointManager())
         {
-            disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(int)), this, SLOT(updateCurrentWaypoint(int)));
+            disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
             disconnect(mav->getWaypointManager(), SIGNAL(waypointDistanceChanged(double)), this, SLOT(updateWaypointDistance(double)));
         }
     }
@@ -234,6 +234,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
     }
 
     // Update all values once
+    systemName = mav->getUASName();
     toolBarNameLabel->setText(mav->getUASName());
     toolBarNameLabel->setStyleSheet(QString("QLabel { font: bold 16px; color: %1; }").arg(mav->getColor().name()));
     symbolButton->setStyleSheet(QString("QWidget { background-color: %1; 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 4px 0px 20px; background-color: none; }").arg(mav->getColor().name()));
diff --git a/src/ui/designer/QGCCommandButton.cc b/src/ui/designer/QGCCommandButton.cc
index d4cebf6..8f09ad0 100644
--- a/src/ui/designer/QGCCommandButton.cc
+++ b/src/ui/designer/QGCCommandButton.cc
@@ -170,12 +170,15 @@ void QGCCommandButton::readSettings(const QSettings& settings)
     }
 
     ui->editParamsVisibleCheckBox->setChecked(settings.value("QGC_COMMAND_BUTTON_PARAMS_VISIBLE").toBool());
-    if (ui->editParamsVisibleCheckBox->isChecked()) {
+    if (ui->editParamsVisibleCheckBox->isChecked())
+    {
         ui->editParam1SpinBox->show();
         ui->editParam2SpinBox->show();
         ui->editParam3SpinBox->show();
         ui->editParam4SpinBox->show();
-    } else {
+    }
+    else
+    {
         ui->editParam1SpinBox->hide();
         ui->editParam2SpinBox->hide();
         ui->editParam3SpinBox->hide();
diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc
index c1651e3..1f85dc2 100644
--- a/src/ui/designer/QGCParamSlider.cc
+++ b/src/ui/designer/QGCParamSlider.cc
@@ -20,6 +20,7 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
     ui(new Ui::QGCParamSlider)
 {
     ui->setupUi(this);
+    ui->intValueSpinBox->hide();
     uas = NULL;
 
     scaledInt = ui->valueSlider->maximum() - ui->valueSlider->minimum();
@@ -45,12 +46,14 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
     connect(ui->editSelectComponentComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectComponent(int)));
     connect(ui->editSelectParamComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(selectParameter(int)));
     connect(ui->valueSlider, SIGNAL(valueChanged(int)), this, SLOT(setSliderValue(int)));
-    connect(ui->valueSpinBox, SIGNAL(valueChanged(double)), this, SLOT(setParamValue(double)));
+    connect(ui->doubleValueSpinBox, SIGNAL(valueChanged(double)), this, SLOT(setParamValue(double)));
+    connect(ui->intValueSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setParamValue(int)));
     connect(ui->editNameLabel, SIGNAL(textChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
     connect(ui->readButton, SIGNAL(clicked()), this, SLOT(requestParameter()));
     connect(ui->editRefreshParamsButton, SIGNAL(clicked()), this, SLOT(refreshParamList()));
 
     // Set the current UAS if present
+    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
     setActiveUAS(UASManager::instance()->getActiveUAS());
 
     // Get param value
@@ -66,21 +69,26 @@ void QGCParamSlider::refreshParamList()
 {
     ui->editSelectParamComboBox->setEnabled(true);
     ui->editSelectComponentComboBox->setEnabled(true);
-    if (uas) {
+    if (uas)
+    {
         uas->getParamManager()->requestParameterList();
     }
 }
 
 void QGCParamSlider::setActiveUAS(UASInterface* activeUas)
 {
-    if (activeUas) {
-        if (uas) {
-            disconnect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(setParameterValue(int,int,int,int,QString,float)));
+    if (activeUas)
+    {
+        if (uas)
+        {
+            disconnect(uas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)));
         }
 
         // Connect buttons and signals
-        connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,float)), this, SLOT(setParameterValue(int,int,int,int,QString,float)), Qt::UniqueConnection);
+        connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection);
         uas = activeUas;
+        // Update current param value
+        requestParameter();
     }
 }
 
@@ -98,6 +106,12 @@ void QGCParamSlider::setParamValue(double value)
     ui->valueSlider->setValue(floatToScaledInt(value));
 }
 
+void QGCParamSlider::setParamValue(int value)
+{
+    parameterValue = value;
+    ui->valueSlider->setValue(floatToScaledInt(value));
+}
+
 void QGCParamSlider::selectComponent(int componentIndex)
 {
     this->component = ui->editSelectComponentComboBox->itemData(componentIndex).toInt();
@@ -111,7 +125,8 @@ void QGCParamSlider::selectParameter(int paramIndex)
 void QGCParamSlider::startEditMode()
 {
     ui->valueSlider->hide();
-    ui->valueSpinBox->hide();
+    ui->doubleValueSpinBox->hide();
+    ui->intValueSpinBox->hide();
     ui->nameLabel->hide();
     ui->writeButton->hide();
     ui->readButton->hide();
@@ -156,7 +171,21 @@ void QGCParamSlider::endEditMode()
     ui->writeButton->show();
     ui->readButton->show();
     ui->valueSlider->show();
-    ui->valueSpinBox->show();
+    switch (parameterValue.type())
+    {
+    case QVariant::Int:
+        ui->intValueSpinBox->show();
+        break;
+    case QVariant::UInt:
+        ui->intValueSpinBox->show();
+        break;
+    case QMetaType::Float:
+        ui->doubleValueSpinBox->show();
+        break;
+    default:
+        qCritical() << "ERROR: NO VALID PARAM TYPE";
+        return;
+    }
     ui->nameLabel->show();
     isInEditMode = false;
     emit editingFinished();
@@ -164,10 +193,20 @@ void QGCParamSlider::endEditMode()
 
 void QGCParamSlider::sendParameter()
 {
-    if (uas) {
+    if (uas)
+    {
         // Set value, param manager handles retransmission
-        uas->getParamManager()->setParameter(component, parameterName, parameterValue);
-    } else {
+        if (uas->getParamManager())
+        {
+            uas->getParamManager()->setParameter(component, parameterName, parameterValue);
+        }
+        else
+        {
+            qDebug() << "UAS HAS NO PARAM MANAGER, DOING NOTHING";
+        }
+    }
+    else
+    {
         qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
     }
 }
@@ -175,9 +214,21 @@ void QGCParamSlider::sendParameter()
 void QGCParamSlider::setSliderValue(int sliderValue)
 {
     parameterValue = scaledIntToFloat(sliderValue);
-    ui->valueSpinBox->setValue(parameterValue);
-//    QString unit("");
-//    ui->valueLabel->setText(QString("%1 %2").arg(parameterValue, 6, 'f', 6, ' ').arg(unit));
+    switch (parameterValue.type())
+    {
+    case QVariant::Int:
+        ui->intValueSpinBox->setValue(parameterValue.toInt());
+        break;
+    case QVariant::UInt:
+        ui->intValueSpinBox->setValue(parameterValue.toUInt());
+        break;
+    case QMetaType::Float:
+        ui->doubleValueSpinBox->setValue(parameterValue.toFloat());
+        break;
+    default:
+        qCritical() << "ERROR: NO VALID PARAM TYPE";
+        return;
+    }
 }
 
 /**
@@ -186,38 +237,67 @@ void QGCParamSlider::setSliderValue(int sliderValue)
  * @brief parameterName Key/name of the parameter
  * @brief value Value of the parameter
  */
-void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, float value)
+void QGCParamSlider::setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, QVariant value)
 {
     Q_UNUSED(paramCount);
     // Check if this component and parameter are part of the list
     bool found = false;
-    for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i) {
-        if (component == ui->editSelectComponentComboBox->itemData(i).toInt()) {
+    for (int i = 0; i< ui->editSelectComponentComboBox->count(); ++i)
+    {
+        if (component == ui->editSelectComponentComboBox->itemData(i).toInt())
+        {
             found = true;
         }
     }
 
-    if (!found) {
+    if (!found)
+    {
         ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(component), component);
     }
 
     // Parameter checking
     found = false;
-    for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i) {
-        if (parameterName == ui->editSelectParamComboBox->itemText(i)) {
+    for (int i = 0; i < ui->editSelectParamComboBox->count(); ++i)
+    {
+        if (parameterName == ui->editSelectParamComboBox->itemText(i))
+        {
             found = true;
         }
     }
 
-    if (!found) {
+    if (!found)
+    {
         ui->editSelectParamComboBox->addItem(parameterName, paramIndex);
     }
 
     Q_UNUSED(uas);
-    if (component == this->component && parameterName == this->parameterName) {
+    if (component == this->component && parameterName == this->parameterName)
+    {
         parameterValue = value;
-        ui->valueSpinBox->setValue(value);
-        ui->valueSlider->setValue(floatToScaledInt(value));
+        switch (value.type())
+        {
+        case QVariant::Int:
+            ui->intValueSpinBox->show();
+            ui->doubleValueSpinBox->hide();
+            ui->intValueSpinBox->setValue(value.toDouble());
+            ui->intValueSpinBox->setMinimum(-ui->intValueSpinBox->maximum());
+            break;
+        case QVariant::UInt:
+            ui->intValueSpinBox->show();
+            ui->doubleValueSpinBox->hide();
+            ui->intValueSpinBox->setValue(value.toDouble());
+            ui->intValueSpinBox->setMinimum(0);
+            break;
+        case QMetaType::Float:
+            ui->doubleValueSpinBox->setValue(value.toDouble());
+            ui->doubleValueSpinBox->show();
+            ui->intValueSpinBox->hide();
+            break;
+        default:
+            qCritical() << "ERROR: NO VALID PARAM TYPE";
+            return;
+        }
+        ui->valueSlider->setValue(floatToScaledInt(value.toDouble()));
     }
 }
 
diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h
index 94783c5..6e9612d 100644
--- a/src/ui/designer/QGCParamSlider.h
+++ b/src/ui/designer/QGCParamSlider.h
@@ -28,14 +28,17 @@ public slots:
     /** @brief Set the slider value as parameter value */
     void setSliderValue(int sliderValue);
     /** @brief Update the UI with the new parameter value */
-    void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, float value);
+    void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value);
     void writeSettings(QSettings& settings);
     void readSettings(const QSettings& settings);
     void refreshParamList();
     void setActiveUAS(UASInterface *uas);
     void selectComponent(int componentIndex);
     void selectParameter(int paramIndex);
+    /** @brief Set a double parameter value */
     void setParamValue(double value);
+    /** @brief Set an integer parameter value */
+    void setParamValue(int value);
 
 protected slots:
     /** @brief Request the parameter of this widget from the MAV */
@@ -43,7 +46,7 @@ protected slots:
 
 protected:
     QString parameterName;         ///< Key/Name of the parameter
-    float parameterValue;          ///< Value of the parameter
+    QVariant parameterValue;          ///< Value of the parameter
     double parameterScalingFactor; ///< Factor to scale the parameter between slider and true value
     float parameterMin;
     float parameterMax;
diff --git a/src/ui/designer/QGCParamSlider.ui b/src/ui/designer/QGCParamSlider.ui
index f350967..488be8f 100644
--- a/src/ui/designer/QGCParamSlider.ui
+++ b/src/ui/designer/QGCParamSlider.ui
@@ -7,7 +7,7 @@
     <x>0</x>
     <y>0</y>
     <width>789</width>
-    <height>155</height>
+    <height>158</height>
    </rect>
   </property>
   <property name="windowTitle">
@@ -147,7 +147,7 @@
     </widget>
    </item>
    <item row="2" column="2">
-    <widget class="QDoubleSpinBox" name="valueSpinBox">
+    <widget class="QDoubleSpinBox" name="doubleValueSpinBox">
      <property name="minimum">
       <double>-999999999.000000000000000</double>
      </property>
@@ -246,6 +246,16 @@
      </property>
     </widget>
    </item>
+   <item row="2" column="4">
+    <widget class="QSpinBox" name="intValueSpinBox">
+     <property name="minimum">
+      <number>-999999999</number>
+     </property>
+     <property name="maximum">
+      <number>999999999</number>
+     </property>
+    </widget>
+   </item>
   </layout>
  </widget>
  <resources/>
diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc
index b83437b..b3baa64 100644
--- a/src/ui/designer/QGCToolWidget.cc
+++ b/src/ui/designer/QGCToolWidget.cc
@@ -47,7 +47,6 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
     }
 
     this->setWindowTitle(title);
-    //setObjectName(title+"WIDGET");
 
     QList<UASInterface*> systems = UASManager::instance()->getUASList();
     foreach (UASInterface* uas, systems)
@@ -64,8 +63,8 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
 
 QGCToolWidget::~QGCToolWidget()
 {
-    if (mainMenuAction) delete mainMenuAction;
-    QGCToolWidget::instances()->remove(widgetTitle);
+    if (mainMenuAction) mainMenuAction->deleteLater();
+    if (QGCToolWidget::instances()) QGCToolWidget::instances()->remove(widgetTitle);
     delete ui;
 }
 
@@ -99,6 +98,7 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent,
     else
     {
         settings = new QSettings();
+        qDebug() << "LOADING SETTINGS FROM DEFAULT" << settings->fileName();
     }
 
     QList<QGCToolWidget*> newWidgets;
@@ -206,10 +206,12 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile)
     if (!settingsFile.isEmpty())
     {
         settings = new QSettings(settingsFile, QSettings::IniFormat);
+        qDebug() << "STORING SETTINGS TO" << settings->fileName();
     }
     else
     {
         settings = new QSettings();
+        qDebug() << "STORING SETTINGS TO DEFAULT" << settings->fileName();
     }
 
     settings->beginWriteArray("QGC_TOOL_WIDGET_NAMES");
@@ -228,6 +230,12 @@ void QGCToolWidget::storeWidgetsToSettings(QString settingsFile)
     delete settings;
 }
 
+void QGCToolWidget::storeSettings()
+{
+    QSettings settings;
+    storeSettings(settings);
+}
+
 void QGCToolWidget::storeSettings(const QString& settingsFile)
 {
     QSettings settings(settingsFile, QSettings::IniFormat);
@@ -271,6 +279,7 @@ void QGCToolWidget::contextMenuEvent (QContextMenuEvent* event)
     QMenu menu(this);
     menu.addAction(addParamAction);
     menu.addAction(addCommandAction);
+    menu.addSeparator();
     menu.addAction(setTitleAction);
     menu.addAction(exportAction);
     menu.addAction(importAction);
@@ -281,7 +290,6 @@ void QGCToolWidget::contextMenuEvent (QContextMenuEvent* event)
 void QGCToolWidget::hideEvent(QHideEvent* event)
 {
     // Store settings
-    storeWidgetsToSettings();
     QWidget::hideEvent(event);
 }
 
@@ -340,6 +348,7 @@ QList<QGCToolWidgetItem*>* QGCToolWidget::itemList()
 void QGCToolWidget::addParam()
 {
     QGCParamSlider* slider = new QGCParamSlider(this);
+    connect(slider, SIGNAL(destroyed()), this, SLOT(storeSettings()));
     if (ui->hintLabel)
     {
         ui->hintLabel->deleteLater();
@@ -352,6 +361,7 @@ void QGCToolWidget::addParam()
 void QGCToolWidget::addCommand()
 {
     QGCCommandButton* button = new QGCCommandButton(this);
+    connect(button, SIGNAL(destroyed()), this, SLOT(storeSettings()));
     if (ui->hintLabel)
     {
         ui->hintLabel->deleteLater();
@@ -368,6 +378,7 @@ void QGCToolWidget::addToolWidget(QGCToolWidgetItem* widget)
         ui->hintLabel->deleteLater();
         ui->hintLabel = NULL;
     }
+    connect(widget, SIGNAL(destroyed()), this, SLOT(storeSettings()));
     toolLayout->addWidget(widget);
 }
 
@@ -436,7 +447,6 @@ void QGCToolWidget::setTitle(QString title)
     QWidget::setWindowTitle(title);
     if (parent) parent->setWindowTitle(title);
 
-    storeWidgetsToSettings();
     emit titleChanged(title);
     if (mainMenuAction) mainMenuAction->setText(title);
 }
diff --git a/src/ui/designer/QGCToolWidget.h b/src/ui/designer/QGCToolWidget.h
index 8747689..80ab4fc 100644
--- a/src/ui/designer/QGCToolWidget.h
+++ b/src/ui/designer/QGCToolWidget.h
@@ -53,6 +53,8 @@ public slots:
     void storeSettings(QSettings& settings);
     /** @brief Store this widget to a settings file */
     void storeSettings(const QString& settingsFile);
+    /** @brief Store this widget to a settings file */
+    void storeSettings();
     /** @brief Store the view id and dock widget area */
     void setViewVisibilityAndDockWidgetArea(int view, bool visible, Qt::DockWidgetArea area);
 
diff --git a/src/ui/map3D/QGCGoogleEarthView.cc b/src/ui/map3D/QGCGoogleEarthView.cc
index 67550c7..8900ff5 100644
--- a/src/ui/map3D/QGCGoogleEarthView.cc
+++ b/src/ui/map3D/QGCGoogleEarthView.cc
@@ -610,7 +610,8 @@ void QGCGoogleEarthView::updateState()
 
         // Update all MAVs
         QList<UASInterface*> mavs = UASManager::instance()->getUASList();
-        foreach (UASInterface* currMav, mavs) {
+        foreach (UASInterface* currMav, mavs)
+        {
             uasId = currMav->getUASID();
             lat = currMav->getLatitude();
             lon = currMav->getLongitude();
@@ -637,9 +638,9 @@ void QGCGoogleEarthView::updateState()
         // Microsoft API available in Qt - improvements wanted
 
         // First check if a new WP should be created
-//        bool newWaypointPending = .to
         bool newWaypointPending = documentElement("newWaypointPending").toBool();
-        if (newWaypointPending) {
+        if (newWaypointPending)
+        {
             bool coordsOk = true;
             bool ok;
             double latitude = documentElement("newWaypointLatitude").toDouble(&ok);
@@ -648,15 +649,14 @@ void QGCGoogleEarthView::updateState()
             coordsOk &= ok;
             double altitude = documentElement("newWaypointAltitude").toDouble(&ok);
             coordsOk &= ok;
-            if (coordsOk) {
+            if (coordsOk)
+            {
                 // Add new waypoint
-                if (mav) {
+                if (mav)
+                {
                     int nextIndex = mav->getWaypointManager()->getWaypointList().count();
                     Waypoint* wp = new Waypoint(nextIndex, latitude, longitude, altitude, true);
                     wp->setFrame(MAV_FRAME_GLOBAL);
-//                    wp.setLatitude(latitude);
-//                    wp.setLongitude(longitude);
-//                    wp.setAltitude(altitude);
                     mav->getWaypointManager()->addWaypoint(wp);
                 }
             }
@@ -666,7 +666,8 @@ void QGCGoogleEarthView::updateState()
         // Check if a waypoint should be moved
         bool dragWaypointPending = documentElement("dragWaypointPending").toBool();
 
-        if (dragWaypointPending) {
+        if (dragWaypointPending)
+        {
             bool coordsOk = true;
             bool ok;
             double latitude = documentElement("dragWaypointLatitude").toDouble(&ok);
@@ -677,21 +678,27 @@ void QGCGoogleEarthView::updateState()
             coordsOk &= ok;
 
             // UPDATE WAYPOINTS, HOME LOCATION AND OTHER LOCATIONS
-            if (coordsOk) {
+            if (coordsOk)
+            {
                 QString idText = documentElement("dragWaypointIndex").toString();
-                if (idText == "HOME") {
+                if (idText == "HOME")
+                {
                     qDebug() << "HOME UPDATED!";
                     UASManager::instance()->setHomePosition(latitude, longitude, altitude);
                     ui->setHomeButton->setChecked(false);
-                } else {
+                }
+                else
+                {
                     // Update waypoint or symbol
-                    if (mav) {
+                    if (mav)
+                    {
                         QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
 
                         bool ok;
                         int index = idText.toInt(&ok);
 
-                        if (ok && index >= 0 && index < wps.count()) {
+                        if (ok && index >= 0 && index < wps.count())
+                        {
                             Waypoint* wp = wps.at(index);
                             wp->setLatitude(latitude);
                             wp->setLongitude(longitude);
@@ -700,7 +707,9 @@ void QGCGoogleEarthView::updateState()
                         }
                     }
                 }
-            } else {
+            }
+            else
+            {
                 // If coords were not ok, move the view in google earth back
                 // to last acceptable location
                 updateWaypointList(mav->getUASID());
diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc
index d9d15c5..74dae8c 100644
--- a/src/ui/uas/UASView.cc
+++ b/src/ui/uas/UASView.cc
@@ -71,7 +71,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
         hilAction(new QAction("Enable Hardware-in-the-Loop Simulation", this )),
         selectAirframeAction(new QAction("Choose Airframe", this)),
         setBatterySpecsAction(new QAction("Set Battery Options", this)),
-        lowPowerModeEnabled(false),
+        lowPowerModeEnabled(true),
         m_ui(new Ui::UASView)
 {
     // FIXME XXX
@@ -140,7 +140,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
     connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh()));
     if (lowPowerModeEnabled)
     {
-        refreshTimer->start(updateInterval*10);
+        refreshTimer->start(updateInterval*3);
     } else {
         refreshTimer->start(updateInterval);
     }