From 1528a1c1946bb99d22042a7383644e2bfeee1c81 Mon Sep 17 00:00:00 2001 From: pixhawk Date: Tue, 18 May 2010 23:03:02 +0200 Subject: [PATCH] minor fixes --- src/comm/MAVLinkSimulationLink.cc | 3 +++ src/uas/UAS.cc | 6 +++--- src/ui/linechart/LinechartPlot.cc | 3 ++- src/ui/linechart/LinechartPlot.h | 7 ++++--- 4 files changed, 12 insertions(+), 7 deletions(-) diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 204b33d08..1111b7e71 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -523,6 +523,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) { mavlink_action_t action; mavlink_msg_action_decode(&msg, &action); + + qDebug() << "SIM" << "received action" << action.action << "for system" << action.target; + switch (action.action) { case MAV_ACTION_LAUNCH: diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 8da437737..bffe71c46 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -834,10 +834,10 @@ void UAS::setWaypoint(Waypoint* wp) mavlink_message_t msg; mavlink_waypoint_set_t set; set.id = wp->id; - QString name = wp->name; + //QString name = wp->name; // FIXME Check if this works properly - name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN); - strcpy((char*)set.name, name.toStdString().c_str()); + //name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN); + //strcpy((char*)set.name, name.toStdString().c_str()); set.autocontinue = wp->autocontinue; set.target_component = 0; set.target_system = uasId; diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index 4dd452401..5f69d5136 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -715,6 +715,7 @@ void TimeSeriesData::append(quint64 ms, double value) } this->ms[count] = ms; this->value[count] = value; + this->lastValue = value; this->mean = 0; QList medianList = QList(); for (unsigned int i = 0; (i < averageWindow) && (((int)count - (int)i) >= 0); ++i) @@ -824,7 +825,7 @@ double TimeSeriesData::getMedian() double TimeSeriesData::getCurrentValue() { - return ms.last(); + return lastValue; } /** diff --git a/src/ui/linechart/LinechartPlot.h b/src/ui/linechart/LinechartPlot.h index d415f71e3..5df6f9a66 100644 --- a/src/ui/linechart/LinechartPlot.h +++ b/src/ui/linechart/LinechartPlot.h @@ -149,9 +149,10 @@ protected: quint64 plotCount; QString friendlyName; - double minValue; - double maxValue; - double zeroValue; + double lastValue; ///< The last inserted value + double minValue; ///< The smallest value in the dataset + double maxValue; ///< The largest value in the dataset + double zeroValue; ///< The expected value in the dataset QMutex dataMutex; -- 2.22.0