Commit 7d4452f0 authored by Gus Grubba's avatar Gus Grubba

Merge pull request #2736 from dogmaphobic/generalCleanup

General cleanup
parents 0064bb76 e7c6e1bb
......@@ -206,11 +206,6 @@ FORMS += \
src/ui/MainWindow.ui \
src/QGCQmlWidgetHolder.ui \
!iOSBuild {
FORMS += \
src/ui/SerialSettings.ui \
}
!MobileBuild {
FORMS += \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
......@@ -309,7 +304,6 @@ contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
HEADERS += \
src/comm/QGCSerialPortInfo.h \
src/comm/SerialLink.h \
src/ui/SerialConfigurationWindow.h \
}
!MobileBuild {
......@@ -420,7 +414,6 @@ SOURCES += \
SOURCES += \
src/comm/QGCSerialPortInfo.cc \
src/comm/SerialLink.cc \
src/ui/SerialConfigurationWindow.cc \
}
contains(DEFINES, QGC_ENABLE_BLUETOOTH) {
......
......@@ -34,7 +34,7 @@ FactPanel {
}
VehicleSummaryRow {
labelText: "WiFi Channel:"
valueText: wifiChannel.valueString
valueText: wifiChannel ? wifiChannel.valueString : ""
}
VehicleSummaryRow {
labelText: "WiFi SSID:"
......@@ -46,7 +46,7 @@ FactPanel {
}
VehicleSummaryRow {
labelText: "UART Baud Rate:"
valueText: uartBaud.valueString
valueText: uartBaud ? uartBaud.valueString : ""
}
}
}
......@@ -18,15 +18,15 @@ FactPanel {
property Fact sysIdFact: controller.getParameterFact(-1, "MAV_SYS_ID")
property Fact sysAutoStartFact: controller.getParameterFact(-1, "SYS_AUTOSTART")
property bool autoStartSet: sysAutoStartFact.value != 0
property bool autoStartSet: sysAutoStartFact ? (sysAutoStartFact.value !== 0) : false
Column {
anchors.fill: parent
anchors.fill: parent
anchors.margins: 8
VehicleSummaryRow {
labelText: "System ID:"
valueText: sysIdFact.valueString
valueText: sysIdFact ? sysIdFact.valueString : ""
}
VehicleSummaryRow {
......@@ -39,4 +39,4 @@ FactPanel {
valueText: autoStartSet ? controller.currentVehicleName : "Setup required"
}
}
}
\ No newline at end of file
}
......@@ -25,22 +25,22 @@ FactPanel {
VehicleSummaryRow {
labelText: "Mode switch:"
valueText: modeSwFact.value == 0 ? "Setup required" : modeSwFact.valueString
valueText: modeSwFact ? (modeSwFact.value === 0 ? "Setup required" : modeSwFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Position Ctl switch:"
valueText: posCtlSwFact.value == 0 ? "Disabled" : posCtlSwFact.valueString
valueText: posCtlSwFact ? (posCtlSwFact.value === 0 ? "Disabled" : posCtlSwFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Loiter switch:"
valueText: loiterSwFact.value == 0 ? "Disabled" : loiterSwFact.valueString
valueText: loiterSwFact ? (loiterSwFact.value === 0 ? "Disabled" : loiterSwFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Return switch:"
valueText: returnSwFact.value == 0 ? "Disabled" : returnSwFact.valueString
valueText: returnSwFact ? (returnSwFact.value === 0 ? "Disabled" : returnSwFact.valueString) : ""
}
}
}
......@@ -28,37 +28,37 @@ FactPanel {
VehicleSummaryRow {
labelText: "Roll:"
valueText: mapRollFact.value == 0 ? "Setup required" : mapRollFact.valueString
valueText: mapRollFact ? (mapRollFact.value === 0 ? "Setup required" : mapRollFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Pitch:"
valueText: mapPitchFact.value == 0 ? "Setup required" : mapPitchFact.valueString
valueText: mapPitchFact ? (mapPitchFact.value === 0 ? "Setup required" : mapPitchFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Yaw:"
valueText: mapYawFact.value == 0 ? "Setup required" : mapYawFact.valueString
valueText: mapYawFact ? (mapYawFact.value === 0 ? "Setup required" : mapYawFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Throttle:"
valueText: mapThrottleFact.value == 0 ? "Setup required" : mapThrottleFact.valueString
valueText: mapThrottleFact ? (mapThrottleFact.value === 0 ? "Setup required" : mapThrottleFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Flaps:"
valueText: mapFlapsFact.value == 0 ? "Disabled" : mapFlapsFact.valueString
valueText: mapFlapsFact ? (mapFlapsFact.value === 0 ? "Disabled" : mapFlapsFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Aux1:"
valueText: mapAux1Fact.value == 0 ? "Disabled" : mapAux1Fact.valueString
valueText: mapAux1Fact ? (mapAux1Fact.value === 0 ? "Disabled" : mapAux1Fact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Aux2:"
valueText: mapAux2Fact.value == 0 ? "Disabled" : mapAux2Fact.valueString
valueText: mapAux2Fact ? (mapAux2Fact.value === 0 ? "Disabled" : mapAux2Fact.valueString) : ""
}
}
}
......@@ -51,17 +51,17 @@ FactPanel {
VehicleSummaryRow {
labelText: "Battery Full:"
valueText: batVChargedFact.valueString
valueText: batVChargedFact ? batVChargedFact.valueString : ""
}
VehicleSummaryRow {
labelText: "Battery Empty:"
valueText: batVEmptyFact.valueString
valueText: batVEmptyFact ? batVEmptyFact.valueString : ""
}
VehicleSummaryRow {
labelText: "Number of Cells:"
valueText: batCellsFact.valueString
valueText: batCellsFact ? batCellsFact.valueString : ""
}
}
}
\ No newline at end of file
}
......@@ -26,27 +26,27 @@ FactPanel {
VehicleSummaryRow {
labelText: "RTL min alt:"
valueText: returnAltFact.valueString
valueText: returnAltFact ? returnAltFact.valueString : ""
}
VehicleSummaryRow {
labelText: "RTL home alt:"
valueText: descendAltFact.valueString
valueText: descendAltFact ? descendAltFact.valueString : ""
}
VehicleSummaryRow {
labelText: "RTL loiter delay:"
valueText: landDelayFact.value < 0 ? "Disabled" : landDelayFact.valueString
valueText: landDelayFact ? (landDelayFact.value < 0 ? "Disabled" : landDelayFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "Telemetry loss RTL:"
valueText: commDLLossFact.value != -1 ? "Disabled" : commDLLossFact.valueString
valueText: commDLLossFact ? (commDLLossFact.value != -1 ? "Disabled" : commDLLossFact.valueString) : ""
}
VehicleSummaryRow {
labelText: "RC loss RTL (seconds):"
valueText: commRCLossFact.valueString
valueText: commRCLossFact ? commRCLossFact.valueString : ""
}
}
}
......@@ -29,17 +29,17 @@ FactPanel {
VehicleSummaryRow {
labelText: "Compass:"
valueText: mag0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: mag0IdFact ? (mag0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
VehicleSummaryRow {
labelText: "Gyro:"
valueText: gyro0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: gyro0IdFact ? (gyro0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
VehicleSummaryRow {
labelText: "Accelerometer:"
valueText: accel0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: accel0IdFact ? (accel0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
}
}
\ No newline at end of file
}
......@@ -29,22 +29,22 @@ FactPanel {
VehicleSummaryRow {
labelText: "Compass:"
valueText: mag0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: mag0IdFact ? (mag0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
VehicleSummaryRow {
labelText: "Gyro:"
valueText: gyro0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: gyro0IdFact ? (gyro0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
VehicleSummaryRow {
labelText: "Accelerometer:"
valueText: accel0IdFact.value == 0 ? "Setup required" : "Ready"
valueText: accel0IdFact ? (accel0IdFact.value === 0 ? "Setup required" : "Ready") : ""
}
VehicleSummaryRow {
labelText: "Airspeed:"
valueText: dpressOffFact.value == 0 ? "Setup required" : "Ready"
valueText: dpressOffFact ? (dpressOffFact.value === 0 ? "Setup required" : "Ready") : ""
}
}
}
......@@ -11,8 +11,8 @@ import QGroundControl.Controls 1.0
QGCTextField {
id: _textField
text: fact.valueString
unitsLabel: fact.units
text: fact ? fact.valueString : ""
unitsLabel: fact ? fact.units : ""
showUnits: true
property Fact fact: null
......
......@@ -514,7 +514,7 @@ void MissionController::_initAllMissionItems(void)
homeItem->setCoordinate(QGeoCoordinate(37.803784, -122.462276, 0.0));
}
qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate();
//qDebug() << "home item" << homeItem->homePositionValid() << homeItem->coordinate();
for (int i=0; i<_missionItems->count(); i++) {
_initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
......
......@@ -52,7 +52,8 @@ void QGCDockWidget::closeEvent(QCloseEvent* event)
void QGCDockWidget::loadSettings(void)
{
if (_action) {
// TODO: This is crashing for some reason. Disabled until sorted out.
if (0 /*_action*/) {
QSettings settings;
settings.beginGroup(_settingsGroup);
if (settings.contains(_title)) {
......@@ -64,7 +65,8 @@ void QGCDockWidget::loadSettings(void)
void QGCDockWidget::saveSettings(void)
{
if (_action) {
// TODO: This is crashing for some reason. Disabled until sorted out.
if (0 /*_action*/) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_title, saveGeometry());
......
......@@ -119,7 +119,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::geocode(const QString &address, int l
url.setQuery(query);
request.setUrl(url);
qDebug() << url;
//qDebug() << url;
QNetworkReply *reply = m_networkManager->get(request);
reply->setParent(0);
......@@ -150,7 +150,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::reverseGeocode(const QGeoCoordinate &
url.setQuery(query);
request.setUrl(url);
qDebug() << url;
//qDebug() << url;
QNetworkReply *reply = m_networkManager->get(request);
reply->setParent(0);
......
......@@ -271,7 +271,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QSettings settings;
QDir airframeDir = QFileInfo(settings.fileName()).dir();
QString airframeFilename = airframeDir.filePath("PX4AirframeFactMetaData.xml");
qDebug() << airframeFilename;
//qDebug() << airframeFilename;
QFile airframeFile(airframeFilename);
if (airframeFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
......
......@@ -95,7 +95,7 @@ Rectangle {
text: setupComplete ?
"Below you will find a summary of the settings for your vehicle. To the left are the setup menus for each component." :
"WARNING: Your vehicle requires setup prior to flight. Please resolve the items marked in red using the menu on the left."
property bool setupComplete: multiVehicleManager.activeVehicle.autopilot.setupComplete
property bool setupComplete: multiVehicleManager.activeVehicle ? multiVehicleManager.activeVehicle.autopilot.setupComplete : false
}
Flow {
......@@ -104,7 +104,7 @@ Rectangle {
spacing: _summaryBoxSpace
Repeater {
model: multiVehicleManager.activeVehicle.autopilot.vehicleComponents
model: multiVehicleManager.activeVehicle ? multiVehicleManager.activeVehicle.autopilot.vehicleComponents : undefined
// Outer summary item rectangle
Rectangle {
......
......@@ -24,87 +24,89 @@ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
/// @file
/// @author Don Gagne <don@thegagnes.com>
import QtQuick 2.2
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0
ViewWidget {
connectedComponent: commandComponenet
Component {
id: commandComponenet
Item {
id: bogusFactPanel
// We aren't really using the controller in a FactPanel for this usage so we
// pass in a bogus item to keep it from getting upset.
CustomCommandWidgetController { id: controller; factPanel: bogusFactPanel }
Item {
anchors.top: parent.top
anchors.bottom: buttonRow.top
width: parent.width
QGCLabel {
id: errorOutput
anchors.fill: parent
wrapMode: Text.WordWrap
visible: false
}
QGCLabel {
id: warning
anchors.fill: parent
wrapMode: Text.WordWrap
visible: !controller.customQmlFile
text: "You can create your own commands and parameter editing user interface in this widget. " +
"You do this by providing your own Qml file. " +
"This support is a work in progress and the details may change somewhat in the future. " +
"By using this feature you are connecting directly to the internals of QGroundControl. " +
"Doing so incorrectly may cause instability both in QGroundControl and/or your vehicle. " +
"So make sure to test your changes thoroughly before using them in flight.\n\n" +
"Click 'Select Qml file' to provide your custom qml file.\n" +
"Click 'Clear Qml file' to reset to none.\n" +
"Example usage: http://www.qgroundcontrol.org/custom_command_qml_widgets"
}
Loader {
id: loader
anchors.fill: parent
source: controller.customQmlFile
visible: controller.customQmlFile
onStatusChanged: {
if (loader.status == Loader.Error) {
if (sourceComponent.status == Component.Error) {
errorOutput.text = sourceComponent.errorString()
errorOutput.visible = true
loader.visible = false
}
import QtQuick 2.5
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QtQuick.Dialogs 1.2
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0
QGCView {
viewPanel: panel
property real _margins: ScreenTools.defaultFontPixelHeight
property string _emptyText: "<p>" +
"You can create your own commands and parameter editing user interface in this widget. " +
"You do this by providing your own Qml file. " +
"This support is a work in progress and the details may change somewhat in the future. " +
"By using this feature you are connecting directly to the internals of QGroundControl. " +
"Doing so incorrectly may cause instability both in QGroundControl and/or your vehicle. " +
"So make sure to test your changes thoroughly before using them in flight.</p>" +
"<p>Click 'Load Custom Qml file' to provide your custom qml file.</p>" +
"<p>Click 'Reset' to reset to none.</p>" +
"<p>Example usage: http://www.qgroundcontrol.org/custom_command_qml_widgets</p>"
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
CustomCommandWidgetController { id: controller; factPanel: panel }
QGCViewPanel {
id: panel
anchors.fill: parent
Rectangle {
anchors.fill: parent
color: qgcPal.window
QGCLabel {
id: textOutput
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
anchors.bottom: buttonRow.top
wrapMode: Text.WordWrap
textFormat: Text.RichText
text: _emptyText
visible: !loader.visible
}
Loader {
id: loader
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
anchors.bottom: buttonRow.top
source: controller.customQmlFile
visible: false
onStatusChanged: {
loader.visible = true
if (loader.status == Loader.Error) {
if (sourceComponent.status == Component.Error) {
textOutput.text = sourceComponent.errorString()
loader.visible = false
}
}
}
}
Row {
id: buttonRow
spacing: 10
anchors.bottom: parent.bottom
id: buttonRow
spacing: ScreenTools.defaultFontPixelWidth
anchors.margins: _margins
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
QGCButton {
text: "Select Qml file..."
text: "Load Custom Qml file..."
width: ScreenTools.defaultFontPixelWidth * 22
onClicked: controller.selectQmlFile()
}
QGCButton {
text: "Clear Qml file"
text: "Reset"
width: ScreenTools.defaultFontPixelWidth * 22
onClicked: {
errorOutput.visible = false
controller.clearQmlFile()
loader.visible = false
textOutput.text = _emptyText
}
}
}
......
......@@ -36,32 +36,30 @@ const char* CustomCommandWidgetController::_settingsKey = "CustomCommand.QmlFile
CustomCommandWidgetController::CustomCommandWidgetController(void) :
_uas(NULL)
{
_uas = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->uas();
Q_ASSERT(_uas);
if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) {
_uas = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->uas();
}
QSettings settings;
_customQmlFile = settings.value(_settingsKey).toString();
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &CustomCommandWidgetController::_activeVehicleChanged);
}
void CustomCommandWidgetController::sendCommand(int commandId, QVariant componentId, QVariant confirm, QVariant param1, QVariant param2, QVariant param3, QVariant param4, QVariant param5, QVariant param6, QVariant param7)
{
Q_UNUSED(commandId);
Q_UNUSED(componentId);
Q_UNUSED(confirm);
Q_UNUSED(param1);
Q_UNUSED(param2);
Q_UNUSED(param3);
Q_UNUSED(param4);
Q_UNUSED(param5);
Q_UNUSED(param6);
Q_UNUSED(param7);
_uas->executeCommand((MAV_CMD)commandId, confirm.toInt(), param1.toFloat(), param2.toFloat(), param3.toFloat(), param4.toFloat(), param5.toFloat(), param6.toFloat(), param7.toFloat(), componentId.toInt());
if(_uas) {
_uas->executeCommand((MAV_CMD)commandId, confirm.toInt(), param1.toFloat(), param2.toFloat(), param3.toFloat(), param4.toFloat(), param5.toFloat(), param6.toFloat(), param7.toFloat(), componentId.toInt());
}
}
void CustomCommandWidgetController::_activeVehicleChanged(Vehicle* activeVehicle)
{
if(activeVehicle)
_uas = activeVehicle->uas();
}
void CustomCommandWidgetController::selectQmlFile(void)
{
QSettings settings;
QString qmlFile = QGCFileDialog::getOpenFileName(NULL, "Select custom Qml file", QString(), "Qml files (*.qml)");
if (qmlFile.isEmpty()) {
_customQmlFile.clear();
......@@ -71,7 +69,6 @@ void CustomCommandWidgetController::selectQmlFile(void)
_customQmlFile = url.toString();
settings.setValue(_settingsKey, _customQmlFile);
}
emit customQmlFileChanged(_customQmlFile);
}
......
......@@ -39,17 +39,20 @@ public:
Q_PROPERTY(QString customQmlFile MEMBER _customQmlFile NOTIFY customQmlFileChanged)
Q_INVOKABLE void sendCommand(int commandId, QVariant componentId, QVariant confirm, QVariant param1, QVariant param2, QVariant param3, QVariant param4, QVariant param5, QVariant param6, QVariant param7);
Q_INVOKABLE void selectQmlFile(void);
Q_INVOKABLE void clearQmlFile(void);
Q_INVOKABLE void sendCommand (int commandId, QVariant componentId, QVariant confirm, QVariant param1, QVariant param2, QVariant param3, QVariant param4, QVariant param5, QVariant param6, QVariant param7);
Q_INVOKABLE void selectQmlFile (void);
Q_INVOKABLE void clearQmlFile (void);
signals:
void customQmlFileChanged(const QString& customQmlFile);
void customQmlFileChanged (const QString& customQmlFile);
private slots:
void _activeVehicleChanged (Vehicle* activeVehicle);
private:
UASInterface* _uas;
QString _customQmlFile;
static const char* _settingsKey;
};
#endif
\ No newline at end of file
#endif
......@@ -101,6 +101,14 @@ public:
/// @return true: This link is replaying a log file, false: Normal two-way communication link
virtual bool isLogReplay(void) { return false; }
/**
* @Enable/Disable data rate collection
**/
void enableDataRate(bool enable)
{
_enableRateCollection = enable;
}
/**
* @Brief Get the current incoming data rate.
*
......@@ -192,6 +200,7 @@ protected:
QThread(0)
, _mavlinkChannelSet(false)
, _active(false)
, _enableRateCollection(false)
{
// Initialize everything for the data rate calculation buffers.
_inDataIndex = 0;
......@@ -211,7 +220,8 @@ protected:
/// @param byteCount Number of bytes received
/// @param time Time in ms send occured
void _logInputDataRate(quint64 byteCount, qint64 time) {
_logDataRateToBuffer(_inDataWriteAmounts, _inDataWriteTimes, &_inDataIndex, byteCount, time);
if(_enableRateCollection)
_logDataRateToBuffer(_inDataWriteAmounts, _inDataWriteTimes, &_inDataIndex, byteCount, time);
}
/// This function logs the send times and amounts of datas for output. Data is used for calculating
......@@ -219,7 +229,8 @@ protected:
/// @param byteCount Number of bytes sent
/// @param time Time in ms receive occured
void _logOutputDataRate(quint64 byteCount, qint64 time) {
_logDataRateToBuffer(_outDataWriteAmounts, _outDataWriteTimes, &_outDataIndex, byteCount, time);
if(_enableRateCollection)
_logDataRateToBuffer(_outDataWriteAmounts, _outDataWriteTimes, &_outDataIndex, byteCount, time);
}
protected slots:
......@@ -354,6 +365,7 @@ private:
mutable QMutex _dataRateMutex; // Mutex for accessing the data rate member variables
bool _active; ///< true: link is actively receiving mavlink messages
bool _enableRateCollection;
};
typedef QSharedPointer<LinkInterface> SharedLinkInterface;
......
......@@ -46,7 +46,7 @@ TCPLink::TCPLink(TCPConfiguration *config)
// We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
moveToThread(this);
qDebug() << "TCP Created " << _config->name();
//qDebug() << "TCP Created " << _config->name();
}
TCPLink::~TCPLink()
......
......@@ -99,8 +99,6 @@ UDPLink::UDPLink(UDPConfiguration* config)
// We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
moveToThread(this);
//qDebug() << "UDP Created " << _config->name();
}
UDPLink::~UDPLink()
......@@ -140,7 +138,7 @@ void UDPLink::run()
if(!_running)
break;
//-- Settle down (it gets here if there is nothing to read or write)
this->msleep(5);
_socket->waitForReadyRead(5);
}
} else {
exec();
......
......@@ -2146,7 +2146,7 @@ void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 p
valueMin,
valueMax);
_vehicle->sendMessage(message);
qDebug() << "Mavlink message sent";
//qDebug() << "Mavlink message sent";
}
void UAS::unsetRCToParameterMap()
......
......@@ -161,7 +161,7 @@ void QGCMAVLinkLogPlayer::_enablePlaybackControls(bool enabled)
void QGCMAVLinkLogPlayer::_setAccelerationFromSlider(int value)
{
qDebug() << value;
//qDebug() << value;
if (_replayLink) {
_replayLink->setAccelerationFactor(value);
}
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Implementation of SerialConfigurationWindow
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QDir>
#include <QSettings>
#include <QFileInfoList>
#include <QDebug>
#ifdef __android__
#include "qserialportinfo.h"
#else
#include <QSerialPortInfo>
#endif
#include <SerialConfigurationWindow.h>
#include <SerialLink.h>
#ifndef USE_ANCIENT_RATES
#define USE_ANCIENT_RATES 0
#endif
SerialConfigurationWindow::SerialConfigurationWindow(SerialConfiguration *config, QWidget *parent, Qt::WindowFlags flags)
: QWidget(parent, flags)
{
_ui.setupUi(this);
Q_ASSERT(config != NULL);
_config = config;
// Scan for serial ports. Let the user know if none were found for debugging purposes
if (!setupPortList()) {
qDebug() << "No serial ports found.";
}
// Set up baud rates
_ui.baudRate->clear();
// Keep track of all desired baud rates by OS. These are iterated through
// later and added to _ui.baudRate.
QStringList supportedBaudRates = SerialConfiguration::supportedBaudRates();
// Now actually add all of our supported baud rates to the ui.
for (int i = 0; i < supportedBaudRates.size(); ++i) {
_ui.baudRate->addItem(supportedBaudRates.at(i), supportedBaudRates.at(i).toInt());
}
// Connect the individual user interface inputs
connect(_ui.portName, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged),
this, &SerialConfigurationWindow::setPortName);
connect(_ui.baudRate, static_cast<void (QComboBox::*)(int)>(&QComboBox::activated),
this, &SerialConfigurationWindow::setBaudRate);
connect(_ui.dataBitsSpinBox, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged),
this, &SerialConfigurationWindow::setDataBits);
connect(_ui.stopBitsSpinBox, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged),
this, &SerialConfigurationWindow::setStopBits);
connect(_ui.flowControlCheckBox,&QCheckBox::toggled, this, &SerialConfigurationWindow::enableFlowControl);
connect(_ui.parNone, &QRadioButton::toggled, this, &SerialConfigurationWindow::setParityNone);
connect(_ui.parOdd, &QRadioButton::toggled, this, &SerialConfigurationWindow::setParityOdd);
connect(_ui.parEven, &QRadioButton::toggled, this, &SerialConfigurationWindow::setParityEven);
connect(_ui.advCheckBox, &QCheckBox::clicked, _ui.advGroupBox, &QWidget::setVisible);
_ui.advCheckBox->setCheckable(true);
_ui.advCheckBox->setChecked(false);
_ui.advGroupBox->setVisible(false);
switch(_config->parity()) {
case QSerialPort::NoParity:
_ui.parNone->setChecked(true);
break;
case QSerialPort::OddParity:
_ui.parOdd->setChecked(true);
break;
case QSerialPort::EvenParity:
_ui.parEven->setChecked(true);
break;
default:
// Enforce default: no parity in link
setParityNone(true);
_ui.parNone->setChecked(true);
break;
}
int idx = 0;
_ui.flowControlCheckBox->setChecked(_config->flowControl() == QSerialPort::HardwareControl);
idx = _ui.baudRate->findText(QString("%1").arg(_config->baud()));
if(idx < 0) idx = _ui.baudRate->findText("57600");
if(idx < 0) idx = 0;
_ui.baudRate->setCurrentIndex(idx);
_ui.dataBitsSpinBox->setValue(_config->dataBits());
_ui.stopBitsSpinBox->setValue(_config->stopBits());
_portCheckTimer = new QTimer(this);
_portCheckTimer->setInterval(1000);
connect(_portCheckTimer, &QTimer::timeout, this, &SerialConfigurationWindow::setupPortList);
// Display the widget
setWindowTitle(tr("Serial Communication Settings"));
}
SerialConfigurationWindow::~SerialConfigurationWindow()
{
}
void SerialConfigurationWindow::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
_portCheckTimer->start();
}
void SerialConfigurationWindow::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
_portCheckTimer->stop();
}
bool SerialConfigurationWindow::setupPortList()
{
bool changed = false;
// Iterate found ports
QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
foreach (const QSerialPortInfo &info, portList)
{
QString name = info.portName();
// Append newly found port to the list
if (_ui.portName->findText(name) < 0)
{
// We show the user the "short name" but store the full port name
_ui.portName->addItem(name, QVariant(info.systemLocation()));
changed = true;
}
}
// See if configured port (if any) is present
if(changed) {
int idx = _ui.portName->count() - 1;
if(!_config->portName().isEmpty()) {
idx = _ui.portName->findData(QVariant(_config->portName()));
if(idx < 0) {
idx = 0;
}
}
_ui.portName->setCurrentIndex(idx);
if(_ui.portName->count() > 0) {
_ui.portName->setEditText(_ui.portName->itemText(idx));
}
if(_config->portName().isEmpty()) {
setPortName(idx);
}
}
return (_ui.portName->count() > 0);
}
void SerialConfigurationWindow::enableFlowControl(bool flow)
{
_config->setFlowControl(flow ? QSerialPort::HardwareControl : QSerialPort::NoFlowControl);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
void SerialConfigurationWindow::setParityNone(bool accept)
{
if (accept) {
_config->setParity(QSerialPort::NoParity);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
}
void SerialConfigurationWindow::setParityOdd(bool accept)
{
if (accept) {
_config->setParity(QSerialPort::OddParity);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
}
void SerialConfigurationWindow::setParityEven(bool accept)
{
if (accept) {
_config->setParity(QSerialPort::EvenParity);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
}
void SerialConfigurationWindow::setPortName(int index)
{
// Get the full port name and store it in the config
QString pname = _ui.portName->itemData(index).toString();
if (_config->portName() != pname) {
_config->setPortName(pname);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
}
void SerialConfigurationWindow::setBaudRate(int index)
{
int baud = _ui.baudRate->itemData(index).toInt();
_config->setBaud(baud);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
void SerialConfigurationWindow::setDataBits(int bits)
{
_config->setDataBits(bits);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
void SerialConfigurationWindow::setStopBits(int bits)
{
_config->setStopBits(bits);
//-- If this was dynamic, it's now edited and persistent
_config->setDynamic(false);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of configuration window for serial links
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _SERIALCONFIGURATIONWINDOW_H_
#define _SERIALCONFIGURATIONWINDOW_H_
#include <QObject>
#include <QWidget>
#include <QTimer>
#include <QShowEvent>
#include <QHideEvent>
#include "SerialLink.h"
#include "ui_SerialSettings.h"
class SerialConfigurationWindow : public QWidget
{
Q_OBJECT
public:
SerialConfigurationWindow(SerialConfiguration* config, QWidget *parent = 0, Qt::WindowFlags flags = Qt::Sheet);
~SerialConfigurationWindow();
public slots:
void enableFlowControl(bool flow);
void setParityNone(bool accept);
void setParityOdd(bool accept);
void setParityEven(bool accept);
void setPortName(int index);
void setBaudRate(int index);
void setDataBits(int bits);
void setStopBits(int bits);
/**
* @brief setupPortList Populates the dropdown with the list of available serial ports.
* This function is called at 1s intervals to check that the serial port still exists and to see if
* any new ones have been attached.
* @return True if any ports were found, false otherwise.
*/
bool setupPortList();
protected:
void showEvent(QShowEvent* event);
void hideEvent(QHideEvent* event);
bool userConfigured; ///< Switch to detect if current values are user-selected and shouldn't be overriden
private:
Ui::serialSettings _ui;
SerialConfiguration* _config;
QTimer* _portCheckTimer;
};
#endif // _SERIALCONFIGURATIONWINDOW_H_
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment