diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 204b33d08cec4b05f32c9f5940060f7d02ace025..1111b7e7186cd9bb059d02cbb87f701212c13de3 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 8da4377374965b4ca696d943e3658a6ff60f9b6d..bffe71c46028d6614b3d8a0287760e07827051f0 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 4dd452401541fd3af02f41757411a4bfcc0c9a01..5f69d513679e51cbd2b5f601efc7f1b8aec7e9d5 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 d415f71e31a846ccff1398486728bd5fdf7e6d2b..5df6f9a667cc62abae6443fbeeb7075508b74022 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;