diff --git a/libs/qwt/qwt_math.h b/libs/qwt/qwt_math.h index 15a7fa673faadf9c4fe4ed832ad5bf748924eb7c..305b220a61acb9d4a99579c87d7e3f4d3fe04711 100644 --- a/libs/qwt/qwt_math.h +++ b/libs/qwt/qwt_math.h @@ -23,8 +23,8 @@ #else // QT_VERSION >= 0x040000 -#define qwtMax qMax -#define qwtMin qMin +#define qwtMax(x,y) qMax(qreal(x),qreal(y)) +#define qwtMin(x,y) qMin(qreal(x),qreal(y)) #define qwtAbs qAbs #endif diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index c98b84a700de13cf68455cc838154ea810e86a98..018611c23ff2f283f4479a26ea0bf5e9f0409c10 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2000,7 +2000,7 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message) */ float UAS::filterVoltage(float value) const { - return lpVoltage * 0.7f + value * 0.3f; + return lpVoltage * 0.6f + value * 0.4f; } /** @@ -2551,110 +2551,76 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName, parameters.insert(compId, new QMap()); } - // Insert parameter into registry - if (parameters.value(compId)->contains(paramName)) { - parameters.value(compId)->remove(paramName); - } QVariant param; // Insert with correct type // TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling. - switch (rawValue.param_type) - { - case MAV_PARAM_TYPE_REAL32: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant(paramValue.param_float); - } - else { - param = QVariant(paramValue.param_float); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); -// qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_UINT8: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant(QChar((unsigned char)paramValue.param_float)); - } - else { - param = QVariant(QChar((unsigned char)paramValue.param_uint8)); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); - //qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_INT8: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant(QChar((char)paramValue.param_float)); - } - else { - param = QVariant(QChar((char)paramValue.param_int8)); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); - //qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_INT16: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant((short)paramValue.param_float); - } - else { - param = QVariant(paramValue.param_int16); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); - //qDebug() << "RECEIVED PARAM:" << param; - } - break; - case MAV_PARAM_TYPE_UINT32: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant((unsigned int)paramValue.param_float); - } - else { - param = QVariant(paramValue.param_uint32); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); - } - break; - case MAV_PARAM_TYPE_INT32: - { - if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { - param = QVariant((int)paramValue.param_float); - } - else { - param = QVariant(paramValue.param_int32); - } - parameters.value(compId)->insert(paramName, param); - // Emit change - emit parameterChanged(uasId, compId, paramName, param); - emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); -// qDebug() << "RECEIVED PARAM:" << param; - } - break; - default: - qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type; + switch (rawValue.param_type) { + case MAV_PARAM_TYPE_REAL32: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant(paramValue.param_float); + } else { + param = QVariant(paramValue.param_float); + } + break; + case MAV_PARAM_TYPE_UINT8: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant(QChar((unsigned char)paramValue.param_float)); + } else { + param = QVariant(QChar((quint8)paramValue.param_float)); + } + break; + case MAV_PARAM_TYPE_INT8: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant(QChar((char)paramValue.param_float)); + } else { + param = QVariant(QChar((qint8)paramValue.param_float)); + } + break; + case MAV_PARAM_TYPE_INT16: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant((short)paramValue.param_float); + } else { + param = QVariant((qint16)paramValue.param_float); + } + break; + case MAV_PARAM_TYPE_UINT16: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant((unsigned short)paramValue.param_float); + } else { + param = QVariant((quint16)paramValue.param_float); + } + break; + case MAV_PARAM_TYPE_UINT32: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant((unsigned int)paramValue.param_float); + } else { + param = QVariant((quint32)paramValue.param_float); + } + break; + case MAV_PARAM_TYPE_INT32: + if (getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { + param = QVariant((int)paramValue.param_float); + } else { + param = QVariant((qint32)paramValue.param_float); + } + break; + default: + qCritical() << "INVALID DATA TYPE USED AS PARAMETER VALUE: " << rawValue.param_type; + return; } //switch (value.param_type) + + // We did not return a critical error, now insert parameter into registry + if (parameters.value(compId)->contains(paramName)) { + parameters.value(compId)->remove(paramName); + } + // add new values + parameters.value(compId)->insert(paramName, param); + // Emit change + emit parameterChanged(uasId, compId, paramName, param); + emit parameterChanged(uasId, compId, rawValue.param_count, rawValue.param_index, paramName, param); } /** diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index 936ffb9957e44a37faa2e7e40d287bdf1d45b0b7..10b1a85960c3aaba778248edfc7abc9a6bcd959d 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -50,7 +50,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : rcThrottle(0.0f), rcMode(0.0f), rcAssist(0.0f), - rcMission(0.0f), + rcLoiter(0.0f), rcReturn(0.0f), rcFlaps(0.0f), rcAux1(0.0f), @@ -72,7 +72,7 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) : channelNames << "Throttle"; channelNames << "Main Mode Switch"; channelNames << "Assist Switch"; - channelNames << "Mission Switch"; + channelNames << "Loiter Switch"; channelNames << "Return Switch"; channelNames << "Flaps"; channelNames << "Aux1"; @@ -1484,7 +1484,7 @@ void QGCPX4VehicleConfig::remoteControlChannelRawChanged(int chan, float fval) rcAssist = normalized; // ASSIST SWITCH } else if (chan == rcMapping[6]) { - rcMission = normalized; // MISSION SWITCH + rcLoiter = normalized; // LOITER SWITCH } else if (chan == rcMapping[7]) { rcReturn = normalized; // RETURN SWITCH @@ -1948,7 +1948,7 @@ void QGCPX4VehicleConfig::updateRcChanLabels() } if (rcValue[rcMapping[6]] != UINT16_MAX) { - ui->missionSwChanLabel->setText(labelForRcValue(rcMission)); + ui->missionSwChanLabel->setText(labelForRcValue(rcLoiter)); } else { ui->missionSwChanLabel->setText(blankLabel); diff --git a/src/ui/QGCPX4VehicleConfig.h b/src/ui/QGCPX4VehicleConfig.h index 976415281df8f76a957fea568a6c3348fb9bff21..103d169d48584bc597154baa9b69beb6130cff83 100644 --- a/src/ui/QGCPX4VehicleConfig.h +++ b/src/ui/QGCPX4VehicleConfig.h @@ -306,7 +306,7 @@ protected: float rcThrottle; ///< PPM input channel used as throttle control input float rcMode; ///< PPM input channel used as mode switch control input float rcAssist; ///< PPM input channel used as assist switch control input - float rcMission; ///< PPM input channel used as mission switch control input + float rcLoiter; ///< PPM input channel used as loiter switch control input float rcReturn; ///< PPM input channel used as return switch control input float rcFlaps; ///< PPM input channel used as flaps control input float rcAux1; ///< PPM input channel used as aux 1 input diff --git a/src/ui/designer/QGCXYPlot.cc b/src/ui/designer/QGCXYPlot.cc index 079e27eeae027e2b47f99f63eee746616b610a1e..a258feedf2cda0cb59503b85e558c7eb654bef1e 100644 --- a/src/ui/designer/QGCXYPlot.cc +++ b/src/ui/designer/QGCXYPlot.cc @@ -33,23 +33,28 @@ public: /** Append data, returning the number of removed items */ int appendData(const QPointF &data) { - if(!minMaxSet) { - xmin = xmax = data.x(); - ymin = ymax = data.y(); - minMaxSet = true; - } else if(m_autoScale) { - xmin = qMin(xmin, data.x()); - xmax = qMax(xmax, data.x()); - ymin = qMin(ymin, data.y()); - ymax = qMax(ymax, data.y()); - } - m_data.append(data); int removed = 0; - while(m_data.size() > m_maxStorePoints) { + while (m_data.size() > m_maxShowPoints) { ++removed; m_data.removeFirst(); } + if (!minMaxSet) { + xmin = xmax = data.x(); + ymin = ymax = data.y(); + minMaxSet = true; + previousTime =xmin; + } else if (m_autoScale) { + if (m_autoScaleTime) { + xmin += removed * (data.x() - previousTime); + previousTime = data.x(); + } else { + xmin = qMin(qreal(xmin), data.x()); + } + xmax = qMax(qreal(xmax), data.x()); + ymin = qMin(qreal(ymin), data.y()); + ymax = qMax(qreal(ymax), data.y()); + } itemChanged(); return removed; } @@ -61,6 +66,10 @@ public: void setColor(const QColor &color) { m_color = color; } + void setTimeSerie(bool state) { + clear(); + m_autoScaleTime = state; + } void unsetMinMax() { if(m_autoScale) return; @@ -70,13 +79,13 @@ public: minMaxSet = false; else { minMaxSet = true; - xmax = xmin = m_data.at(0).x(); + previousTime = xmax = xmin = m_data.at(0).x(); ymax = ymin = m_data.at(0).y(); for(int i = 1; i < m_data.size(); i++) { - xmin = qMin(xmin, m_data.at(i).x()); - xmax = qMax(xmax, m_data.at(i).x()); - ymin = qMin(ymin, m_data.at(i).y()); - ymax = qMax(ymax, m_data.at(i).y()); + xmin = qMin(qreal(xmin), m_data.at(i).x()); + xmax = qMax(qreal(xmax), m_data.at(i).x()); + ymin = qMin(qreal(ymin), m_data.at(i).y()); + ymax = qMax(qreal(ymax), m_data.at(i).y()); } } } @@ -164,12 +173,14 @@ private: int m_smoothPoints; /** Number of points to average across */ mutable QColor m_color; + double previousTime; double xmin; double xmax; double ymin; double ymax; bool minMaxSet; bool m_autoScale; + bool m_autoScaleTime; int m_startIndex; }; @@ -220,6 +231,7 @@ QGCXYPlot::QGCXYPlot(QWidget *parent) : connect(ui->minY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings())); connect(ui->maxY, SIGNAL(valueChanged(double)),this, SLOT(updateMinMaxSettings())); connect(ui->automaticAxisRange, SIGNAL(toggled(bool)),this, SLOT(updateMinMaxSettings())); + connect(ui->timeAxisRange, SIGNAL(toggled(bool)),this, SLOT(setTimeAxis())); connect(ui->maxDataShowSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); connect(ui->maxDataStoreSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); connect(ui->smoothSpinBox, SIGNAL(valueChanged(int)),this, SLOT(updateMinMaxSettings())); @@ -261,6 +273,7 @@ void QGCXYPlot::setEditMode(bool editMode) ui->maxDataShowSpinBox->setVisible(editMode); ui->maxDataStoreSpinBox->setVisible(editMode); ui->automaticAxisRange->setVisible(editMode); + ui->timeAxisRange->setVisible(editMode); ui->lblSmooth->setVisible(editMode); ui->smoothSpinBox->setVisible(editMode); @@ -286,7 +299,7 @@ void QGCXYPlot::writeSettings(QSettings& settings) settings.setValue("QGC_XYPLOT_MAXDATA_SHOW", ui->maxDataShowSpinBox->value()); settings.setValue("QGC_XYPLOT_AUTO", ui->automaticAxisRange->isChecked()); settings.setValue("QGC_XYPLOT_SMOOTH", ui->smoothSpinBox->value()); - + settings.setValue("QGC_XYPLOT_TIME", ui->timeAxisRange->isChecked()); settings.sync(); } void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings) @@ -301,6 +314,7 @@ void QGCXYPlot::readSettings(const QString& pre,const QVariantMap& settings) ui->maxDataStoreSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_STORE", 10000).toInt()); ui->maxDataShowSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_MAXDATA_SHOW", 15).toInt()); ui->smoothSpinBox->setValue(settings.value(pre + "QGC_XYPLOT_SMOOTH", 1).toInt()); + ui->timeAxisRange->setChecked(settings.value(pre + "QGC_XYPLOT_TIME", true).toBool()); plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText()); plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText()); updateMinMaxSettings(); @@ -318,6 +332,7 @@ void QGCXYPlot::readSettings(const QSettings& settings) ui->maxDataStoreSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_STORE", 10000).toInt()); ui->maxDataShowSpinBox->setValue(settings.value("QGC_XYPLOT_MAXDATA_SHOW", 15).toInt()); ui->smoothSpinBox->setValue(settings.value("QGC_XYPLOT_SMOOTH", 1).toInt()); + ui->timeAxisRange->setChecked(settings.value("QGC_XYPLOT_TIME", true).toBool()); plot->setAxisTitle(QwtPlot::xBottom, ui->editXParam->currentText()); plot->setAxisTitle(QwtPlot::yLeft, ui->editYParam->currentText()); updateMinMaxSettings(); @@ -412,6 +427,11 @@ void QGCXYPlot::updateMinMaxSettings() xycurve->setSmoothPoints(ui->smoothSpinBox->value()); } +void QGCXYPlot::setTimeAxis() +{ + xycurve->setTimeSerie(ui->timeAxisRange->isChecked()); +} + void QGCXYPlot::on_maxDataShowSpinBox_valueChanged(int value) { ui->maxDataStoreSpinBox->setMinimum(value); diff --git a/src/ui/designer/QGCXYPlot.h b/src/ui/designer/QGCXYPlot.h index 1b4818d8899d579f94148020f07bd2b59ce4c3cc..d574f2ee4da25f28eec355ace2d4b3d72744b053 100644 --- a/src/ui/designer/QGCXYPlot.h +++ b/src/ui/designer/QGCXYPlot.h @@ -31,10 +31,11 @@ public slots: void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style); void updateMinMaxSettings(); + private slots: void on_maxDataShowSpinBox_valueChanged(int value); void on_stopStartButton_toggled(bool checked); - + void setTimeAxis(); void on_timeScrollBar_valueChanged(int value); private: @@ -42,6 +43,7 @@ private: QwtPlot *plot; XYPlotCurve* xycurve; + bool autoScaleTime; double x; /**< Last unused value for the x-coordinate */ quint64 x_timestamp_us; /**< Timestamp that we last recieved a value for x */ bool x_valid; /**< Whether we have recieved an x value but so far no corresponding y value */