From 8da2820d402d052c2643bfcf002f29df7d07a650 Mon Sep 17 00:00:00 2001 From: lm Date: Wed, 5 Jan 2011 16:29:21 +0100 Subject: [PATCH] Fixed ground time button YEEHAY! --- src/uas/UAS.cc | 7 +++++-- src/uas/UAS.h | 2 +- src/uas/UASInterface.h | 8 +++++++- src/ui/HUD.cc | 2 +- src/ui/linechart/LinechartPlot.cc | 5 ++++- 5 files changed, 18 insertions(+), 6 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 073c940ee..39882258e 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1259,8 +1259,10 @@ void UAS::enableExtra3Transmission(int rate) * @param id Name of the parameter * @param value Parameter value */ -void UAS::setParameter(int component, QString id, float value) -{ +void UAS::setParameter(const int component, const QString& id, const float value) +{ + if (!id.isNull()) + { mavlink_message_t msg; mavlink_param_set_t p; p.param_value = value; @@ -1288,6 +1290,7 @@ void UAS::setParameter(int component, QString id, float value) } mavlink_msg_param_set_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &p); sendMessage(msg); + } } /** diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 410b15e4a..bb0333184 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -239,7 +239,7 @@ public slots: void requestParameters(); /** @brief Set a system parameter */ - void setParameter(int component, QString id, float value); + void setParameter(const int component, const QString& id, const float value); /** @brief Write parameters to permanent storage */ void writeParametersToStorage(); diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 8bbc716b9..0b0041990 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -214,7 +214,7 @@ public slots: * @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it * @param value Value of the parameter, IEEE 754 single precision floating point */ - virtual void setParameter(int component, QString id, float value) = 0; + virtual void setParameter(const int component, const QString& id, const float value) = 0; /** * @brief Add a link to the list of current links @@ -327,8 +327,14 @@ signals: * @param value the value that changed * @param msec the timestamp of the message, in milliseconds */ + + // FIXME Exchange the lines below against the commented ones void valueChanged(int uasId, QString name, double value, quint64 msec); void valueChanged(UASInterface* uas, QString name, double value, quint64 msec); + +// void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec); +// //void valueChanged(UASInterface* uas, QString name, double value, quint64 msec); + void voltageChanged(int uasId, double voltage); void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active); void waypointSelected(int uasId, int id); diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 083267174..2d5726236 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -285,7 +285,7 @@ void HUD::updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double void HUD::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp) { - qDebug() << __FILE__ << __LINE__ << "ROLL" << yaw; + //qDebug() << __FILE__ << __LINE__ << "YAW" << yaw; updateValue(uas, "roll", roll, timestamp); updateValue(uas, "pitch", pitch, timestamp); updateValue(uas, "yaw", yaw, timestamp); diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index 49194b5fa..606c3bddf 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -254,7 +254,8 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) if(ms < minTime) minTime = ms; if(ms > maxTime) maxTime = ms; storageInterval = maxTime - minTime; - lastTime = time; + + if(time > lastTime) lastTime = time; // if (value < minValue) minValue = value; @@ -276,6 +277,8 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value) void LinechartPlot::enforceGroundTime(bool enforce) { m_groundTime = enforce; + + lastTime = QGC::groundTimeUsecs()/1000; } /** -- 2.22.0