diff --git a/src/qgcunittest/UASUnitTest.cc b/src/qgcunittest/UASUnitTest.cc index b6c11b0f9284e938b2b6e1a673e7822a7a5d6ae4..2fc948c2469a59f471e6e5726b4008507405137f 100644 --- a/src/qgcunittest/UASUnitTest.cc +++ b/src/qgcunittest/UASUnitTest.cc @@ -73,15 +73,20 @@ void UASUnitTest::getCommunicationStatus_test() void UASUnitTest::filterVoltage_test() { float verificar=uas->filterVoltage(0.4f); - // Verify that upon construction the Comm status is disconnected - QCOMPARE(verificar, 8.52f); + + // We allow the voltage returned to be within a small delta + const float allowedDelta = 0.05f; + const float desiredVoltage = 7.36f; + QVERIFY(verificar > (desiredVoltage - allowedDelta) && verificar < (desiredVoltage + allowedDelta)); } + void UASUnitTest:: getAutopilotType_test() { int type = uas->getAutopilotType(); // Verify that upon construction the autopilot is set to -1 QCOMPARE(type, -1); } + void UASUnitTest::setAutopilotType_test() { uas->setAutopilotType(2); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index fd6cfb7db18e446ac8eff23a5f4fd9a444e7cc4c..98ec5d79d65e370aa83b1a244be910ceb40ba44f 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2552,76 +2552,110 @@ 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); - } - 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 (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 (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/px4_configuration/QGCPX4AirframeConfig.cc b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc index f77111754d23e725bd59b0c4e0e31067d53eeb12..949073732864d8399336edcd87d0ca75c891ce60 100644 --- a/src/ui/px4_configuration/QGCPX4AirframeConfig.cc +++ b/src/ui/px4_configuration/QGCPX4AirframeConfig.cc @@ -99,6 +99,7 @@ QGCPX4AirframeConfig::QGCPX4AirframeConfig(QWidget *parent) : ui->hComboBox->addItem(tr("3DR Iris"), 10016); ui->hComboBox->addItem(tr("TBS Discovery"), 10015); + ui->hComboBox->addItem(tr("SteadiDrone QU4D"), 10017); connect(ui->hPushButton, SIGNAL(clicked()), this, SLOT(hSelected())); connect(ui->hComboBox, SIGNAL(activated(int)), this, SLOT(hSelected(int))); diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc index 61843f6092ed791adcb733bfd6367b856e834f3c..7affc73f143e323898f85deb6bb3c990b2d65758 100644 --- a/src/ui/uas/UASView.cc +++ b/src/ui/uas/UASView.cc @@ -634,16 +634,26 @@ void UASView::refresh() // Thrust m_ui->thrustBar->setValue(thrust * 100); + // Time Elapsed + //QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime()); + + quint64 filterTime = uas->getUptime() / 1000; + int hours = static_cast(filterTime / 3600); + int min = static_cast((filterTime - 3600 * hours) / 60); + int sec = static_cast(filterTime - 60 * min - 3600 * hours); + QString timeText; + timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); + m_ui->timeElapsedLabel->setText(timeText); + if(this->timeRemaining > 1 && this->timeRemaining < QGC::MAX_FLIGHT_TIME) { // Filter output to get a higher stability filterTime = static_cast(this->timeRemaining); - filterTime = 0.8 * filterTime + 0.2 * static_cast(this->timeRemaining); - int sec = static_cast(filterTime - static_cast(filterTime / 60.0f) * 60); - int min = static_cast(filterTime / 60); - int hours = static_cast(filterTime - min * 60 - sec); + // filterTime = 0.8 * filterTime + 0.2 * static_cast(this->timeRemaining); + hours = static_cast(filterTime / 3600); + min = static_cast((filterTime - 3600 * hours) / 60); + sec = static_cast(filterTime - 60 * min - 3600 * hours); - QString timeText; timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); m_ui->timeRemainingLabel->setText(timeText); } @@ -652,16 +662,7 @@ void UASView::refresh() m_ui->timeRemainingLabel->setText(tr("Calc..")); } - // Time Elapsed - //QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime()); - quint64 filterTime = uas->getUptime() / 1000; - int sec = static_cast(filterTime - static_cast(filterTime / 60) * 60); - int min = static_cast(filterTime / 60); - int hours = static_cast(filterTime - min * 60 - sec); - QString timeText; - timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); - m_ui->timeElapsedLabel->setText(timeText); } generalUpdateCount++;