Commit 2ba6578d authored by Lorenz Meier's avatar Lorenz Meier

Merged in APM config tree

parents 27274cd8 d88d49f6
......@@ -49,7 +49,8 @@ user_config.pri
*.suo
*.uhf.txt
*.opensdf
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
thirdParty/qserialport/lib/
apmplanner2.xcodeproj/
GeneratedFiles/
This diff is collapsed.
......@@ -20,7 +20,8 @@
# Qt configuration
CONFIG += qt \
thread
thread \
console
# serialport
QT += network \
......@@ -265,7 +266,10 @@ FORMS += src/ui/MainWindow.ui \
src/ui/configuration/ArduRoverPidConfig.ui \
src/ui/QGCConfigView.ui \
src/ui/main/QGCViewModeSelection.ui \
src/ui/main/QGCWelcomeMainWindow.ui
src/ui/main/QGCWelcomeMainWindow.ui \
src/ui/configuration/terminalconsole.ui \
src/ui/configuration/SerialSettingsDialog.ui \
src/ui/configuration/ApmFirmwareConfig.ui
INCLUDEPATH += src \
src/ui \
......@@ -378,14 +382,14 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/QGCMapTool.h \
src/ui/map/QGCMapToolBar.h \
# libs/qextserialport/qextserialenumerator.h \
src/QGCGeo.h \
src/ui/QGCToolBar.h \
src/ui/QGCStatusBar.h \
src/ui/QGCMAVLinkInspector.h \
src/ui/MAVLinkDecoder.h \
src/ui/WaypointViewOnlyView.h \
src/ui/WaypointEditableView.h \
src/ui/WaypointEditableView.h \
src/ui/UnconnectedUASInfoWidget.h \
src/ui/QGCRGBDView.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
......@@ -459,7 +463,12 @@ HEADERS += src/MG.h \
src/ui/configuration/ArduRoverPidConfig.h \
src/ui/QGCConfigView.h \
src/ui/main/QGCViewModeSelection.h \
src/ui/main/QGCWelcomeMainWindow.h
src/ui/main/QGCWelcomeMainWindow.h \
src/ui/configuration/console.h \
src/ui/configuration/SerialSettingsDialog.h \
src/ui/configuration/terminalconsole.h \
src/ui/configuration/ApmHighlighter.h \
src/ui/configuration/ApmFirmwareConfig.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -669,7 +678,12 @@ SOURCES += src/main.cc \
src/ui/configuration/ArduRoverPidConfig.cc \
src/ui/QGCConfigView.cc \
src/ui/main/QGCViewModeSelection.cc \
src/ui/main/QGCWelcomeMainWindow.cc
src/ui/main/QGCWelcomeMainWindow.cc \
src/ui/configuration/terminalconsole.cpp \
src/ui/configuration/console.cpp \
src/ui/configuration/SerialSettingsDialog.cc \
src/ui/configuration/ApmHighlighter.cc \
src/ui/configuration/ApmFirmwareConfig.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......@@ -806,7 +820,8 @@ unix:!macx:!symbian: LIBS += -losg
OTHER_FILES += \
dongfang_notes.txt \
src/ui/dongfang-scrapyard.txt \
qml/components/DigitalDisplay.qml
qml/components/DigitalDisplay.qml \
qml/components/StatusDisplay.qml
OTHER_FILES += \
qml/ApmToolBar.qml \
......
......@@ -120,6 +120,43 @@
<file>files/images/actions/qgroundcontrol-apm.svg</file>
<file>files/images/actions/qgroundcontrol-ardrone.svg</file>
<file>files/images/actions/qgroundcontrol-wifi.svg</file>
<file>files/images/firmware/apmcopter.png</file>
<file>files/images/firmware/apmplane.png</file>
<file>files/images/firmware/apmrover.png</file>
<file>files/images/firmware/FW icons 2013+logos.ai</file>
<file>files/images/firmware/heli.png</file>
<file>files/images/firmware/heli_off.png</file>
<file>files/images/firmware/heli_on.png</file>
<file>files/images/firmware/hexa_off.png</file>
<file>files/images/firmware/hexa_on.png</file>
<file>files/images/firmware/hexaplus.png</file>
<file>files/images/firmware/hexax.png</file>
<file>files/images/firmware/hexay.png</file>
<file>files/images/firmware/octaplus.png</file>
<file>files/images/firmware/octax.png</file>
<file>files/images/firmware/octo_off.png</file>
<file>files/images/firmware/octo_on.png</file>
<file>files/images/firmware/octx.png</file>
<file>files/images/firmware/plane.png</file>
<file>files/images/firmware/plane_off.png</file>
<file>files/images/firmware/plane_on.png</file>
<file>files/images/firmware/quad_off.png</file>
<file>files/images/firmware/quad_on.png</file>
<file>files/images/firmware/quad_T_off.png</file>
<file>files/images/firmware/quad_T_on.png</file>
<file>files/images/firmware/quadplus.png</file>
<file>files/images/firmware/quadx.png</file>
<file>files/images/firmware/quady.png</file>
<file>files/images/firmware/rover.png</file>
<file>files/images/firmware/rover_off.png</file>
<file>files/images/firmware/rover_on.png</file>
<file>files/images/firmware/Tir_off.png</file>
<file>files/images/firmware/Tir_on.png</file>
<file>files/images/firmware/triy.png</file>
<file>files/images/firmware/X8.png</file>
<file>files/images/firmware/X8_on.png</file>
<file>files/images/firmware/Y6_off.png</file>
<file>files/images/firmware/Y6_on.png</file>
</qresource>
<qresource prefix="/general">
<file alias="vera.ttf">files/styles/Vera.ttf</file>
......
......@@ -9,12 +9,27 @@ Rectangle {
property alias linkNameLabel: linkDevice.label
property alias baudrateLabel: baudrate.label
property bool connected: false
property bool armed: false
property string armedstr: "DISARMED"
width: toolbar.width
height: 72
color: "black"
border.color: "black"
onArmedChanged: {
if (armed) {
statusDisplay.statusText = "ARMED"
statusDisplay.statusTextColor = "red"
statusDisplay.statusBackgroundColor = "#FF880000"
}
else {
statusDisplay.statusText = "DISARMED"
statusDisplay.statusTextColor = "yellow"
statusDisplay.statusBackgroundColor = "black"
}
}
onConnectedChanged: {
if (connected){
console.log("APM Tool BAR QML: connected")
......@@ -44,7 +59,7 @@ Rectangle {
Row {
anchors.left: parent.left
spacing: 2
spacing: 10
Rectangle { // Spacer
width: 5
......@@ -104,6 +119,20 @@ Rectangle {
color: "black"
}
StatusDisplay {
id: statusDisplay
width: 110
statusText: "DISARMED"
statusTextColor: "yellow"
statusBackgroundColor: "black"
}
Rectangle { // Spacer
width: 5
height: parent.height
color: "black"
}
// [BB] Commented out ToolBar Status info work.
// WIP: To be fixed later
// DigitalDisplay { // Information Pane
......
......@@ -5,7 +5,7 @@ Rectangle {
property alias title: displayTitle.text
property string textValue: "none"
width: 100
width: 110
height: parent.height/3
anchors.verticalCenter: parent.verticalCenter
border.color: "white"
......
import QtQuick 1.1
Rectangle {
id: statusDisplay
property alias statusText: armedText.text
property alias statusTextColor: armedText.color
property alias statusBackgroundColor: statusDisplay.color
width: 100
height: parent.height/3
anchors.verticalCenter: parent.verticalCenter
radius: 3
border.color: "white"
border.width: 1
Text {
id: armedText
anchors.centerIn: parent
verticalAlignment: Text.AlignVCenter
horizontalAlignment: Text.AlignHCenter
font.pixelSize: 20
}
}
......@@ -168,7 +168,16 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc,
// to make sure that all components are initialized when the
// first messages arrive
udpLink = new UDPLink(QHostAddress::Any, 14550);
MainWindow::instance()->addLink(udpLink);
LinkManager::instance()->add(udpLink);
//MainWindow::instance()->addLink(udpLink);
} else if (mainWindow->getCustomMode() == MainWindow::CUSTOM_MODE_PX4) {
udpLink = new UDPLink(QHostAddress::Any, 14550);
LinkManager::instance()->add(udpLink);
SerialLink *slink = new SerialLink();
} else {
// We want to have a default serial link available for "quick" connecting.
SerialLink *slink = new SerialLink();
// MainWindow::instance()->addLink(slink);
}
#ifdef OPAL_RT
......@@ -177,15 +186,12 @@ QGCCore::QGCCore(bool firstStart, int &argc, char* argv[]) : QApplication(argc,
MainWindow::instance()->addLink(opalLink);
#endif
//We want to have a default serial link available for "quick" connecting.
SerialLink *slink = new SerialLink();
MainWindow::instance()->addLink(slink);
// Remove splash screen
splashScreen->finish(mainWindow);
if (upgraded) mainWindow->showInfoMessage(tr("Default Settings Loaded"),
tr("qgroundcontrol has been upgraded from version %1 to version %2. Some of your user preferences have been reset to defaults for safety reasons. Please adjust them where needed.").arg(lastApplicationVersion).arg(QGC_APPLICATION_VERSION));
// Check if link could be connected
if (udpLink && !udpLink->connect())
{
......
......@@ -84,13 +84,13 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
{
// Connect link to protocol
// the protocol will receive new bytes from the link
if(!link || !protocol) return;
if (!link || !protocol) return;
QList<LinkInterface*> linkList = protocolLinks.values(protocol);
// If protocol has not been added before (list length == 0)
// OR if link has not been added to protocol, add
if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0)
if (!linkList.contains(link))
{
// Protocol is new, add
connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
......
......@@ -63,16 +63,6 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
m_dataBits = dataBits;
m_stopBits = stopBits;
// Set the port name
// if (m_portName == "")
// {
// m_name = tr("Serial Link ") + QString::number(getId());
// }
// else
// {
// m_name = portname.trimmed();
// }
loadSettings();
LinkManager::instance()->add(this);
}
......@@ -92,8 +82,6 @@ SerialLink::~SerialLink()
QList<QString> SerialLink::getCurrentPorts()
{
m_ports.clear();
// Example use QSerialPortInfo
// [TODO] make this thread safe
QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
......@@ -153,6 +141,7 @@ void SerialLink::run()
{
//Need to error out here.
emit communicationError(getName(),"Error connecting: " + m_port->errorString());
disconnect(); // This tidies up and sends the necessary signals
return;
}
......@@ -184,18 +173,18 @@ void SerialLink::run()
}
}
if (m_transmitBuffer.size() > 0) {
// send the data
QMutexLocker lockWrite(&m_writeMutex);
int num_written = m_port->write(m_transmitBuffer.constData());
if (num_written > 0){
m_transmitBuffer = m_transmitBuffer.remove(0,num_written);
}
if (m_transmitBuffer.length() > 0) {
QMutexLocker writeLocker(&m_writeMutex);
int numWritten = m_port->write(m_transmitBuffer);
bool txError = m_port->waitForBytesWritten(-1);
// if ((txError) || (numWritten == -1))
// qDebug() << "TX Error!";
m_transmitBuffer = m_transmitBuffer.remove(0, numWritten);
} else {
// qDebug() << "Wait write response timeout %1" << QTime::currentTime().toString();
}
bool error = m_port->waitForReadyRead(500);
bool error = m_port->waitForReadyRead(10);
if(error) { // Waits for 1/2 second [TODO][BB] lower to SerialLink::poll_interval?
QByteArray readData = m_port->readAll();
......@@ -209,9 +198,9 @@ void SerialLink::run()
m_bitsReceivedTotal += readData.length() * 8;
}
} else {
// qDebug() << "readyReadTime #"<< __LINE__;
// qDebug() << "Wait write response timeout %1" << QTime::currentTime().toString();
}
if (bytes != m_bytesRead) // i.e things are good and data is being read.
{
bytes = m_bytesRead;
......@@ -274,20 +263,17 @@ void SerialLink::writeBytes(const char* data, qint64 size)
if(m_port && m_port->isOpen()) {
// qDebug() << "writeBytes" << m_portName << "attempting to tx " << size << "bytes.";
QByteArray byteArray(data,size);
QByteArray byteArray(data, size);
{
QMutexLocker writeLocker(&m_writeMutex);
m_transmitBuffer.append(byteArray);
}
// qDebug() << "writeBytes " << m_portName << "tx'd" << b << "bytes:";
// Increase write counter
m_bitsSentTotal += size * 8;
// Extra debug logging
// qDebug() << byteArray->toHex();
// delete byteArray;
} else {
disconnect();
// Error occured
......@@ -421,6 +407,8 @@ bool SerialLink::hardwareConnect()
}
QObject::connect(m_port,SIGNAL(aboutToClose()),this,SIGNAL(disconnected()));
QObject::connect(m_port, SIGNAL(error(QSerialPort::SerialPortError)),
this, SLOT(linkError(QSerialPort::SerialPortError)));
// port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead);
m_connectionStartTime = MG::TIME::getGroundTimeNow();
......@@ -452,6 +440,11 @@ bool SerialLink::hardwareConnect()
return true; // successful connection
}
void SerialLink::linkError(QSerialPort::SerialPortError error)
{
qDebug() << error;
}
/**
* @brief Check if connection is active.
......
......@@ -142,6 +142,8 @@ public slots:
bool connect();
bool disconnect();
void linkError(QSerialPort::SerialPortError error);
protected:
quint64 m_bytesRead;
QSerialPort* m_port;
......@@ -166,13 +168,13 @@ protected:
quint64 m_connectionStartTime;
QMutex m_statisticsMutex;
QMutex m_dataMutex;
QMutex m_writeMutex;
QList<QString> m_ports;
private:
volatile bool m_stopp;
volatile bool m_reqReset;
QMutex m_stoppMutex;
QMutex m_writeMutex;
QByteArray m_transmitBuffer;
bool hardwareConnect();
......
......@@ -50,6 +50,7 @@ UDPLink::UDPLink(QHostAddress host, quint16 port)
this->name = tr("UDP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
// LinkManager::instance()->add(this);
qDebug() << "UDP Created " << name;
}
UDPLink::~UDPLink()
......@@ -104,7 +105,7 @@ void UDPLink::setPort(int port)
*/
void UDPLink::addHost(const QString& host)
{
//qDebug() << "UDP:" << "ADDING HOST:" << host;
qDebug() << "UDP:" << "ADDING HOST:" << host;
if (host.contains(":"))
{
//qDebug() << "HOST: " << host.split(":").first();
......
......@@ -11,7 +11,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.1.0 (beta)"
#define QGC_APPLICATION_VERSION "v. 1.1.1 (beta)"
namespace QGC
......
......@@ -53,11 +53,17 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
void ArduPilotMegaMAV::sendTxRequests()
{
enableExtendedSystemStatusTransmission(2);
QGC::SLEEP::msleep(250);
enablePositionTransmission(3);
QGC::SLEEP::msleep(250);
enableExtra1Transmission(10);
QGC::SLEEP::msleep(250);
enableExtra2Transmission(10);
QGC::SLEEP::msleep(250);
enableExtra3Transmission(2);
QGC::SLEEP::msleep(250);
enableRawSensorDataTransmission(2);
QGC::SLEEP::msleep(250);
enableRCChannelDataTransmission(2);
}
......
......@@ -73,11 +73,18 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.connectionType->setEnabled(false);
ui.linkType->setEnabled(false);
ui.protocolGroupBox->setVisible(false);
ui.protocolTypeGroupBox->setVisible(false);
// Connect UI element visibility to checkbox
connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.connectionType, SLOT(setEnabled(bool)));
connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.linkType, SLOT(setEnabled(bool)));
connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.protocolGroupBox, SLOT(setVisible(bool)));
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.connectionType, SLOT(setEnabled(bool)));
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.linkType, SLOT(setEnabled(bool)));
//connect(ui.advancedOptionsCheckBox, SIGNAL(clicked(bool)), ui.protocolGroupBox, SLOT(setVisible(bool)));
ui.advancedOptionsCheckBox->setVisible(false);
//connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.advancedOptionsCheckBox,SLOT(setChecked(bool)));
connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.protocolTypeGroupBox,SLOT(setVisible(bool)));
connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.connectionType, SLOT(setEnabled(bool)));
connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.linkType, SLOT(setEnabled(bool)));
connect(ui.advCheckBox, SIGNAL(clicked(bool)), ui.protocolGroupBox, SLOT(setVisible(bool)));
// add link types
ui.linkType->addItem(tr("Serial"), QGC_LINK_SERIAL);
......
......@@ -6,85 +6,15 @@
<rect>
<x>0</x>
<y>0</y>
<width>413</width>
<height>373</height>
<width>324</width>
<height>415</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_2" rowstretch="1,1,1,100,100,1">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>6</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>6</number>
</property>
<item row="0" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>5</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="0" colspan="2">
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Link Type</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="linkType"/>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Protocol</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="connectionType">
<property name="currentIndex">
<number>-1</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QCheckBox" name="advancedOptionsCheckBox">
<property name="text">
<string>Advanced Options</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0" colspan="2">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="3" column="0" colspan="2">
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QGroupBox" name="linkGroupBox">
<property name="title">
<string>Link</string>
......@@ -93,16 +23,7 @@
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<property name="margin">
<number>0</number>
</property>
<item>
......@@ -115,8 +36,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>391</width>
<height>85</height>
<width>302</width>
<height>69</height>
</rect>
</property>
</widget>
......@@ -125,7 +46,65 @@
</layout>
</widget>
</item>
<item row="4" column="0" colspan="2">
<item>
<widget class="QCheckBox" name="advCheckBox">
<property name="text">
<string>Show Advanced Protocol Options</string>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="protocolTypeGroupBox">
<property name="title">
<string>GroupBox</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Link Type</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="linkType"/>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="connectionType">
<property name="currentIndex">
<number>-1</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QCheckBox" name="advancedOptionsCheckBox">
<property name="text">
<string>Advanced Options</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Protocol</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="protocolGroupBox">
<property name="title">
<string>Protocol</string>
......@@ -134,16 +113,7 @@
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<property name="margin">
<number>0</number>
</property>
<item>
......@@ -156,8 +126,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>391</width>
<height>84</height>
<width>302</width>
<height>69</height>
</rect>
</property>
</widget>
......@@ -166,20 +136,20 @@
</layout>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="connectionStatusLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="text">
<string>Disconnected</string>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</widget>
</spacer>
</item>
<item row="5" column="1">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
......@@ -193,7 +163,7 @@
<string>Connect</string>
</property>
<property name="checkable">
<bool>true</bool>
<bool>false</bool>
</property>
</widget>
</item>
......@@ -216,6 +186,19 @@
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="connectionStatusLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Disconnected</string>
</property>
</widget>
</item>
</layout>
<action name="actionDelete">
<property name="text">
......@@ -241,6 +224,13 @@
<string>Close the configuration window</string>
</property>
</action>
<zorder>line</zorder>
<zorder>linkGroupBox</zorder>
<zorder>protocolGroupBox</zorder>
<zorder>connectionStatusLabel</zorder>
<zorder>advCheckBox</zorder>
<zorder>protocolTypeGroupBox</zorder>
<zorder>verticalSpacer</zorder>
</widget>
<resources/>
<connections>
......
This diff is collapsed.
......@@ -200,7 +200,7 @@ public slots:
/** @brief Show the application settings */
void showSettings();
/** @brief Add a communication link */
void addLink();
LinkInterface* addLink();
void addLink(LinkInterface* link);
bool configLink(LinkInterface *link);
void configure();
......@@ -238,6 +238,8 @@ public slots:
void loadMAVLinkView();
/** @brief Load firmware update view */
void loadFirmwareUpdateView();
/** @brief Load Terminal Console views */
void loadTerminalView();
/** @brief Show the online help for users */
void showHelp();
......@@ -334,6 +336,9 @@ protected:
VIEW_FIRMWAREUPDATE,
VIEW_HARDWARE_CONFIG,
VIEW_SOFTWARE_CONFIG,
VIEW_TERMINAL,
VIEW_3DWIDGET,
VIEW_GOOGLEEARTH,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
VIEW_FULL ///< All widgets shown at once
} VIEW_SECTIONS;
......@@ -363,7 +368,7 @@ protected:
* @param widget The QWidget being added
* @param title The entry that will appear in the Menu
*/
void addCentralWidget(QWidget* widget, const QString& title);
void addToCentralStackedWidget(QWidget* widget, VIEW_SECTIONS viewSection, const QString& title);
/** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event);
......@@ -387,7 +392,7 @@ protected:
void storeSettings();
// TODO Should be moved elsewhere, as the protocol does not belong to the UI
MAVLinkProtocol* mavlink;
QPointer<MAVLinkProtocol> mavlink;
LinkInterface* udpLink;
......@@ -403,6 +408,7 @@ protected:
QPointer<SubMainWindow> mavlinkView;
QPointer<SubMainWindow> engineeringView;
QPointer<SubMainWindow> simView;
QPointer<SubMainWindow> terminalView;
// Center widgets
QPointer<Linecharts> linechartWidget;
......@@ -412,10 +418,10 @@ protected:
//QPointer<XMLCommProtocolWidget> protocolWidget;
//QPointer<QGCDataPlot2D> dataplotWidget;
#ifdef QGC_OSG_ENABLED
QPointer<QWidget> _3DWidget;
QPointer<QWidget> q3DWidget;
#endif
#if (defined _MSC_VER) || (defined Q_OS_MAC)
QPointer<QGCGoogleEarthView> gEarthWidget;
QPointer<QGCGoogleEarthView> earthWidget;
#endif
QPointer<QGCFirmwareUpdate> firmwareUpdateWidget;
......
......@@ -99,6 +99,7 @@
<addaction name="actionFlightView"/>
<addaction name="actionHardwareConfig"/>
<addaction name="actionSoftwareConfig"/>
<addaction name="actionTerminalView"/>
<addaction name="actionEngineersView"/>
<addaction name="actionSimulationView"/>
<addaction name="separator"/>
......@@ -466,11 +467,21 @@
</property>
</action>
<action name="actionSimulationView">
<property name="checkable">
<bool>true</bool>
</property>
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/files/images/apps/accessories-calculator.svg</normaloff>:/files/images/apps/accessories-calculator.svg</iconset>
</property>
<property name="text">
<string>Simulation</string>
</property>
</action>
<action name="actionSoftwareConfig">
<property name="checkable">
<bool>true</bool>
</property>
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/files/images/categories/applications-system.svg</normaloff>:/files/images/categories/applications-system.svg</iconset>
......@@ -479,6 +490,18 @@
<string>Software</string>
</property>
</action>
<action name="actionTerminalView">
<property name="checkable">
<bool>true</bool>
</property>
<property name="icon">
<iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/files/images/apps/utilities-terminal.svg</normaloff>:/files/images/apps/utilities-terminal.svg</iconset>
</property>
<property name="text">
<string>Terminal</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -7,10 +7,10 @@ QGCTabbedInfoView::QGCTabbedInfoView(QWidget *parent) : QWidget(parent)
actionsWidget = new UASActionsWidget(this);
quickView = new UASQuickView(this);
rawView = new UASRawStatusView(this);
ui.tabWidget->addTab(messageView,"Messages");
ui.tabWidget->addTab(quickView,"Quick");
ui.tabWidget->addTab(actionsWidget,"Actions");
ui.tabWidget->addTab(rawView,"Status");
ui.tabWidget->addTab(messageView,"Messages");
}
void QGCTabbedInfoView::addSource(MAVLinkDecoder *decoder)
{
......
......@@ -129,10 +129,13 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
connect(ui.parEven, SIGNAL(toggled(bool)), this, SLOT(setParityEven(bool)));
connect(ui.dataBitsSpinBox, SIGNAL(valueChanged(int)), this->link, SLOT(setDataBits(int)));
connect(ui.stopBitsSpinBox, SIGNAL(valueChanged(int)), this->link, SLOT(setStopBits(int)));
connect(ui.advCheckBox,SIGNAL(clicked(bool)),ui.advGroupBox,SLOT(setShown(bool)));
ui.advCheckBox->setChecked(false);
ui.advGroupBox->setVisible(false);
//connect(this->link, SIGNAL(connected(bool)), this, SLOT());
ui.portName->setSizeAdjustPolicy(QComboBox::AdjustToContentsOnFirstShow);
ui.baudRate->setSizeAdjustPolicy(QComboBox::AdjustToContentsOnFirstShow);
//ui.portName->setSizeAdjustPolicy(QComboBox::AdjustToContentsOnFirstShow);
//ui.baudRate->setSizeAdjustPolicy(QComboBox::AdjustToContentsOnFirstShow);
switch(this->link->getParityType()) {
case 0:
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
#include "apmtoolbar.h"
APMToolBar::APMToolBar(QWidget *parent):
QDeclarativeView(parent)
QDeclarativeView(parent), m_uas(0)
{
// Configure our QML object
setSource(QUrl::fromLocalFile("qml/ApmToolBar.qml"));
......@@ -21,6 +21,37 @@ APMToolBar::APMToolBar(QWidget *parent):
}
setConnection(false);
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUasSet(UASInterface*)));
activeUasSet(UASManager::instance()->getActiveUAS());
}
void APMToolBar::activeUasSet(UASInterface *uas)
{
if (!uas)
{
return;
}
if (m_uas)
{
disconnect(m_uas,SIGNAL(armingChanged(bool)),
this,SLOT(armingChanged(bool)));
disconnect(uas,SIGNAL(armingChanged(int, QString)),
this,SLOT(armingChanged(int, QString)));
}
connect(uas,SIGNAL(armingChanged(bool)),
this,SLOT(armingChanged(bool)));
connect(uas,SIGNAL(armingChanged(int, QString)),
this,SLOT(armingChanged(int, QString)));
}
void APMToolBar::armingChanged(bool armed)
{
this->rootObject()->setProperty("armed",armed);
}
void APMToolBar::armingChanged(int sysId, QString armingState)
{
qDebug() << "APMToolBar: sysid " << sysId << " armState" << armingState;
}
void APMToolBar::setFlightViewAction(QAction *action)
......
......@@ -3,6 +3,7 @@
#include <QAction>
#include <QDeclarativeView>
#include "UASInterface.h"
class LinkInterface;
......@@ -43,7 +44,14 @@ public slots:
void showConnectionDialog();
void setConnection(bool connection);
void activeUasSet(UASInterface *uas);
void armingChanged(int sysId, QString armingState);
void armingChanged(bool armed);
void updateLinkDisplay(LinkInterface *newLink);
private:
UASInterface *m_uas;
};
#endif // APMTOOLBAR_H
......@@ -4,9 +4,13 @@
AP2ConfigWidget::AP2ConfigWidget(QWidget *parent) : QWidget(parent)
{
m_uas = 0;
}
void AP2ConfigWidget::initConnections()
{
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
}
void AP2ConfigWidget::activeUASSet(UASInterface *uas)
{
if (m_uas)
......
......@@ -12,6 +12,7 @@ public:
protected:
UASInterface *m_uas;
void showNullMAVErrorMessageBox();
void initConnections();
signals:
public slots:
......
......@@ -6,9 +6,8 @@ AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : AP2ConfigWidge
ui.setupUi(this);
connect(ui.calibrateAccelButton,SIGNAL(clicked()),this,SLOT(calibrateButtonClicked()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
m_accelAckCount=0;
initConnections();
}
AccelCalibrationConfig::~AccelCalibrationConfig()
......@@ -58,9 +57,29 @@ void AccelCalibrationConfig::calibrateButtonClicked()
{
m_uas->executeCommandAck(m_accelAckCount++,true);
ui.calibrateAccelButton->setText("Calibrate\nAccelerometer");
if (m_accelAckCount > 8)
{
//We've clicked too many times! Reset.
for (int i=0;i<8;i++)
{
m_uas->executeCommandAck(i,true);
}
m_accelAckCount = 0;
}
}
}
void AccelCalibrationConfig::hideEvent(QHideEvent *evt)
{
if (!m_uas || !m_accelAckCount)
{
return;
}
for (int i=m_accelAckCount;i<8;i++)
{
m_uas->executeCommandAck(i,true); //Clear out extra commands.
}
}
void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid, int severity, QString text)
{
//command received: " Severity 1
......@@ -71,7 +90,7 @@ void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid,
if (m_accelAckCount == 0)
{
//Calibration Sucessful\r"
ui.calibrateAccelButton->setText("Any\nKey");
ui.calibrateAccelButton->setText("Continue");
m_accelAckCount++;
}
if (m_accelAckCount == 7)
......@@ -87,11 +106,21 @@ void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid,
{
m_accelAckCount = 0;
}
else if (text.contains("Calibration") && text.contains("FAILED")) //Failure
{
m_accelAckCount = 0;
}
ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text);
}
else
{
ui.outputLabel->setText(text);
ui.outputLabel->setText(text.replace("press any key","click Continue below"));
if (!this->isVisible())
{
//Clear out!
m_uas->executeCommandAck(m_accelAckCount++,true);
ui.calibrateAccelButton->setText("Calibrate\nAccelerometer");
}
}
}
......
......@@ -14,6 +14,8 @@ class AccelCalibrationConfig : public AP2ConfigWidget
public:
explicit AccelCalibrationConfig(QWidget *parent = 0);
~AccelCalibrationConfig();
protected:
void hideEvent(QHideEvent *evt);
private slots:
void activeUASSet(UASInterface *uas);
void calibrateButtonClicked();
......
......@@ -11,7 +11,7 @@ AdvParameterList::AdvParameterList(QWidget *parent) : AP2ConfigWidget(parent)
ui.tableWidget->setColumnWidth(1,100);
ui.tableWidget->setColumnWidth(2,200);
ui.tableWidget->setColumnWidth(3,800);
initConnections();
}
AdvParameterList::~AdvParameterList()
......
......@@ -17,7 +17,7 @@
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>&lt;h2&gt;Advanced Parameter List&lt;/h2&gt;</string>
<string>&lt;h2&gt;Full Parameter List&lt;/h2&gt;</string>
</property>
</widget>
</item>
......
......@@ -4,6 +4,7 @@
AdvancedParamConfig::AdvancedParamConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
initConnections();
}
AdvancedParamConfig::~AdvancedParamConfig()
......@@ -11,7 +12,9 @@ AdvancedParamConfig::~AdvancedParamConfig()
}
void AdvancedParamConfig::addRange(QString title,QString description,QString param,double min,double max)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents);
connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double)));
connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int)));
m_paramToWidgetMap[param] = widget;
widget->setupDouble(title + "(" + param + ")",description,0,min,max);
ui.verticalLayout->addWidget(widget);
......@@ -20,7 +23,9 @@ void AdvancedParamConfig::addRange(QString title,QString description,QString par
void AdvancedParamConfig::addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
ParamWidget *widget = new ParamWidget(param,ui.scrollAreaWidgetContents);
connect(widget,SIGNAL(doubleValueChanged(QString,double)),this,SLOT(doubleValueChanged(QString,double)));
connect(widget,SIGNAL(intValueChanged(QString,int)),this,SLOT(intValueChanged(QString,int)));
m_paramToWidgetMap[param] = widget;
widget->setupCombo(title + "(" + param + ")",description,valuelist);
ui.verticalLayout->addWidget(widget);
......@@ -30,6 +35,30 @@ void AdvancedParamConfig::parameterChanged(int uas, int component, QString param
{
if (m_paramToWidgetMap.contains(parameterName))
{
m_paramToWidgetMap[parameterName]->setValue(value.toDouble());
if (value.type() == QVariant::Double)
{
m_paramToWidgetMap[parameterName]->setValue(value.toDouble());
}
else
{
m_paramToWidgetMap[parameterName]->setValue(value.toInt());
}
}
}
void AdvancedParamConfig::doubleValueChanged(QString param,double value)
{
if (!m_uas)
{
this->showNullMAVErrorMessageBox();
}
m_uas->getParamManager()->setParameter(1,param,value);
}
void AdvancedParamConfig::intValueChanged(QString param,int value)
{
if (!m_uas)
{
this->showNullMAVErrorMessageBox();
}
m_uas->getParamManager()->setParameter(1,param,value);
}
......@@ -16,6 +16,8 @@ public:
void addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist);
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void doubleValueChanged(QString param,double value);
void intValueChanged(QString param,int value);
private:
QMap<QString,ParamWidget*> m_paramToWidgetMap;
Ui::AdvancedParamConfig ui;
......
......@@ -6,6 +6,7 @@ AirspeedConfig::AirspeedConfig(QWidget *parent) : AP2ConfigWidget(parent)
ui.setupUi(this);
connect(ui.enableCheckBox,SIGNAL(toggled(bool)),this,SLOT(enableCheckBoxClicked(bool)));
connect(ui.useAirspeedCheckBox,SIGNAL(toggled(bool)),this,SLOT(useCheckBoxClicked(bool)));
initConnections();
}
AirspeedConfig::~AirspeedConfig()
......
This diff is collapsed.
#ifndef APMFIRMWARECONFIG_H
#define APMFIRMWARECONFIG_H
#include <QWidget>
#include <QNetworkAccessManager>
#include <QNetworkRequest>
#include <QNetworkReply>
#include <QDebug>
#include <QTemporaryFile>
#include <QProcess>
#include <QXmlStreamReader>
#include <QMessageBox>
#include <QProcess>
#include <QScrollBar>
#include "qserialport.h"
#include "ui_ApmFirmwareConfig.h"
class ApmFirmwareConfig : public QWidget
{
Q_OBJECT
public:
explicit ApmFirmwareConfig(QWidget *parent = 0);
~ApmFirmwareConfig();
private slots:
void firmwareListFinished();
void firmwareListError(QNetworkReply::NetworkError error);
void flashButtonClicked();
void betaFirmwareButtonClicked(bool betafirmwareenabled);
void downloadFinished();
void firmwareProcessFinished(int status);
void firmwareProcessReadyRead();
void firmwareProcessError(QProcess::ProcessError error);
void firmwareDownloadProgress(qint64 received,qint64 total);
void requestFirmwares();
void requestBetaFirmwares();
private:
void addBetaLabel(QWidget *parent);
void hideBetaLabels();
void showBetaLabels();
//ApmFirmwareStatus *firmwareStatus;
QString m_detectedComPort;
QTemporaryFile *m_tempFirmwareFile;
QNetworkAccessManager *m_networkManager;
QList<QLabel*> m_betaButtonLabelList;
bool stripVersionFromGitReply(QString url,QString reply,QString type,QString stable,QString *out);
bool m_betaFirmwareChecked;
QMap<QPushButton*,QString> m_buttonToUrlMap;
Ui::ApmFirmwareConfig ui;
class FirmwareDef
{
public:
QString url;
QString url2560;
QString url25602;
QString urlpx4;
QString type;
QString name;
QString desc;
int version;
};
QList<FirmwareDef> m_firmwareList;
};
#endif // APMFIRMWARECONFIG_H
This diff is collapsed.
......@@ -60,9 +60,9 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
connect(ui.frameTypeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
QWidget *widget = new QWidget(this);
ui.stackedWidget->addWidget(widget); //Firmware placeholder.
m_buttonToConfigWidgetMap[ui.firmwareButton] = widget;
m_apmFirmwareConfig = new ApmFirmwareConfig(this);
ui.stackedWidget->addWidget(m_apmFirmwareConfig); //Firmware placeholder.
m_buttonToConfigWidgetMap[ui.firmwareButton] = m_apmFirmwareConfig;
connect(ui.firmwareButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
m_frameConfig = new FrameTypeConfig(this);
......
......@@ -49,6 +49,7 @@ This file is part of the QGROUNDCONTROL project
#include "CameraGimbalConfig.h"
#include "AntennaTrackerConfig.h"
#include "ApmPlaneLevel.h"
#include "ApmFirmwareConfig.h"
class ApmHardwareConfig : public QWidget
{
......@@ -58,20 +59,22 @@ public:
explicit ApmHardwareConfig(QWidget *parent = 0);
~ApmHardwareConfig();
private:
FrameTypeConfig *m_frameConfig;
CompassConfig *m_compassConfig;
AccelCalibrationConfig *m_accelConfig;
RadioCalibrationConfig *m_radioConfig;
QPointer<FrameTypeConfig> m_frameConfig;
QPointer<CompassConfig> m_compassConfig;
QPointer<AccelCalibrationConfig> m_accelConfig;
QPointer<RadioCalibrationConfig> m_radioConfig;
QPointer<ApmFirmwareConfig> m_apmFirmwareConfig;
QPointer<Radio3DRConfig> m_radio3drConfig;
QPointer<BatteryMonitorConfig> m_batteryConfig;
QPointer<SonarConfig> m_sonarConfig;
QPointer<AirspeedConfig> m_airspeedConfig;
QPointer<OpticalFlowConfig> m_opticalFlowConfig;
QPointer<OsdConfig> m_osdConfig;
QPointer<CameraGimbalConfig> m_cameraGimbalConfig;
QPointer<AntennaTrackerConfig> m_antennaTrackerConfig;
QPointer<ApmPlaneLevel> m_planeLevel;
Radio3DRConfig *m_radio3drConfig;
BatteryMonitorConfig *m_batteryConfig;
SonarConfig *m_sonarConfig;
AirspeedConfig *m_airspeedConfig;
OpticalFlowConfig *m_opticalFlowConfig;
OsdConfig *m_osdConfig;
CameraGimbalConfig *m_cameraGimbalConfig;
AntennaTrackerConfig *m_antennaTrackerConfig;
ApmPlaneLevel *m_planeLevel;
private slots:
void activeUASSet(UASInterface *uas);
void activateStackedWidget();
......
/*=====================================================================
APM_PLANNER Open Source Ground Control Station
(c) 2013, Bill Bonney <billbonney@communistech.com>
This file is part of the APM_PLANNER project
APM_PLANNER 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.
APM_PLANNER 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 APM_PLANNER. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief APM Highligther for ArduPilot Console.
*
* @author Bill Bonney <billbonney@communistech.com>
*
*/
#include "ApmHighlighter.h"
APMHighlighter::APMHighlighter(QObject *parent) :
QSyntaxHighlighter(parent)
{
}
void APMHighlighter::highlightBlock(const QString &text)
{
QTextCharFormat myClassFormat;
myClassFormat.setFontWeight(QFont::Bold);
myClassFormat.setForeground(Qt::darkMagenta);
QString pattern = "^\\Ardu[A-Za-z]+\\b";
QRegExp expression(pattern);
int index = text.indexOf(expression);
while (index >= 0) {
int length = expression.matchedLength();
setFormat(index, length, myClassFormat);
index = text.indexOf(expression, index + length);
}
}
/*=====================================================================
APM_PLANNER Open Source Ground Control Station
(c) 2013, Bill Bonney <billbonney@communistech.com>
This file is part of the APM_PLANNER project
APM_PLANNER 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.
APM_PLANNER 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 APM_PLANNER. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief APM Highligther for ArduPilot Console.
*
* @author Bill Bonney <billbonney@communistech.com>
*
*/
#ifndef APMHIGHLIGHTER_H
#define APMHIGHLIGHTER_H
#include "ApmHighlighter.h"
#include <QSyntaxHighlighter>
class APMHighlighter : public QSyntaxHighlighter
{
Q_OBJECT
public:
explicit APMHighlighter(QObject *parent = 0);
void highlightBlock(const QString &text);
signals:
public slots:
};
#endif // APMHIGHLIGHTER_H
......@@ -6,6 +6,7 @@ ApmPlaneLevel::ApmPlaneLevel(QWidget *parent) : AP2ConfigWidget(parent)
ui.setupUi(this);
connect(ui.levelPushButton,SIGNAL(clicked()),this,SLOT(levelClicked()));
connect(ui.manualLevelCheckBox,SIGNAL(toggled(bool)),this,SLOT(manualCheckBoxToggled(bool)));
initConnections();
}
ApmPlaneLevel::~ApmPlaneLevel()
......
......@@ -85,23 +85,27 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
ui.advancedParamButton->setVisible(true);
ui.advParamListButton->setVisible(true);
QString compare = "";
if (uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
ui.arduPlanePidButton->setVisible(true);
ui.arduCopterPidButton->setVisible(false);
ui.arduRoverPidButton->setVisible(false);
compare = "ArduPlane";
}
else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
ui.arduCopterPidButton->setVisible(true);
ui.arduPlanePidButton->setVisible(false);
ui.arduRoverPidButton->setVisible(false);
compare = "ArduCopter";
}
else if (uas->getSystemType() == MAV_TYPE_GROUND_ROVER)
{
ui.arduRoverPidButton->setVisible(true);
ui.arduCopterPidButton->setVisible(false);
ui.arduPlanePidButton->setVisible(false);
compare = "APMRover2";
}
......@@ -138,6 +142,7 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
{
parametersname = xml.attributes().value("name").toString();
}
QVariantMap genset;
QVariantMap advset;
......@@ -301,24 +306,25 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
{
valuelist.append(QPair<int,QString>(i.key().toInt(),i.value()));
}
if (tab == "Standard")
{
m_standardParamConfig->addCombo(humanname,docs,name,valuelist);
}
else if (tab == "Advanced")
if (compare == parametersname)
{
m_advancedParamConfig->addCombo(humanname,docs,name,valuelist);
if (tab == "Standard")
{
m_standardParamConfig->addCombo(humanname,docs,name,valuelist);
}
else if (tab == "Advanced")
{
m_advancedParamConfig->addCombo(humanname,docs,name,valuelist);
}
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
else if (fieldmap.size() > 0)
{
float min = 0;
float max = 100;
float max = 65535;
if (fieldmap.contains("Range"))
{
float min = 0;
float max = 0;
//Some range fields list "0-10" and some list "0 10". Handle both.
if (fieldmap["Range"].split(" ").size() > 1)
{
......@@ -331,15 +337,18 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
}
}
if (tab == "Standard")
{
m_standardParamConfig->addRange(humanname,docs,name,min,max);
}
else if (tab == "Advanced")
if (compare == parametersname)
{
m_advancedParamConfig->addRange(humanname,docs,name,max,min);
if (tab == "Standard")
{
m_standardParamConfig->addRange(humanname,docs,name,min,max);
}
else if (tab == "Advanced")
{
m_advancedParamConfig->addRange(humanname,docs,name,min,max);
}
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
}
......
......@@ -28,16 +28,16 @@ private slots:
void activeUASSet(UASInterface *uas);
private:
Ui::ApmSoftwareConfig ui;
BasicPidConfig *m_basicPidConfig;
FlightModeConfig *m_flightConfig;
StandardParamConfig *m_standardParamConfig;
GeoFenceConfig *m_geoFenceConfig;
FailSafeConfig *m_failSafeConfig;
AdvancedParamConfig *m_advancedParamConfig;
ArduCopterPidConfig *m_arduCopterPidConfig;
ArduPlanePidConfig *m_arduPlanePidConfig;
ArduRoverPidConfig *m_arduRoverPidConfig;
AdvParameterList *m_advParameterList;
QPointer<BasicPidConfig> m_basicPidConfig;
QPointer<FlightModeConfig> m_flightConfig;
QPointer<StandardParamConfig> m_standardParamConfig;
QPointer<GeoFenceConfig> m_geoFenceConfig;
QPointer<FailSafeConfig> m_failSafeConfig;
QPointer<AdvancedParamConfig> m_advancedParamConfig;
QPointer<ArduCopterPidConfig> m_arduCopterPidConfig;
QPointer<ArduPlanePidConfig> m_arduPlanePidConfig;
QPointer<ArduRoverPidConfig> m_arduRoverPidConfig;
QPointer<AdvParameterList> m_advParameterList;
QMap<QObject*,QWidget*> m_buttonToConfigWidgetMap;
};
......
......@@ -132,7 +132,7 @@
</size>
</property>
<property name="text">
<string>Adv Parameter List</string>
<string>Full Parameter List</string>
</property>
<property name="checkable">
<bool>false</bool>
......
......@@ -3,6 +3,11 @@
ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
m_pitchRollLocked = false;
connect(ui.checkBox,SIGNAL(clicked(bool)),this,SLOT(lockCheckBoxClicked(bool)));
connect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
connect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
connect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
m_nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox;
m_nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox;
m_nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox;
......@@ -107,6 +112,26 @@ ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(pare
ui.ch7OptComboBox->addItem(m_ch78ValueToTextList[i].second);
ui.ch8OptComboBox->addItem(m_ch78ValueToTextList[i].second);
}
initConnections();
}
void ArduCopterPidConfig::lockCheckBoxClicked(bool checked)
{
m_pitchRollLocked = checked;
}
void ArduCopterPidConfig::stabilLockedChanged(double value)
{
if (m_pitchRollLocked)
{
disconnect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
disconnect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
disconnect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
ui.stabilPitchPSpinBox->setValue(value);
ui.stabilRollPSpinBox->setValue(value);
ui.stabilYawPSpinBox->setValue(value);
connect(ui.stabilPitchPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
connect(ui.stabilRollPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
connect(ui.stabilYawPSpinBox,SIGNAL(valueChanged(double)),this,SLOT(stabilLockedChanged(double)));
}
}
ArduCopterPidConfig::~ArduCopterPidConfig()
......
......@@ -17,7 +17,10 @@ private slots:
void writeButtonClicked();
void refreshButtonClicked();
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void lockCheckBoxClicked(bool checked);
void stabilLockedChanged(double value);
private:
bool m_pitchRollLocked;
QList<QPair<int,QString> > m_ch6ValueToTextList;
QList<QPair<int,QString> > m_ch78ValueToTextList;
QMap<QString,QDoubleSpinBox*> m_nameToBoxMap;
......
......@@ -58,7 +58,7 @@ ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent
connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
initConnections();
}
ArduPlanePidConfig::~ArduPlanePidConfig()
......
......@@ -39,7 +39,7 @@ ArduRoverPidConfig::ArduRoverPidConfig(QWidget *parent) : AP2ConfigWidget(parent
connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
initConnections();
}
ArduRoverPidConfig::~ArduRoverPidConfig()
......
......@@ -31,7 +31,7 @@ BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(pa
connect(ui.battCapacityLineEdit,SIGNAL(editingFinished()),this,SLOT(batteryCapacitySet()));
initConnections();
}
void BatteryMonitorConfig::activeUASSet(UASInterface *uas)
{
......
......@@ -106,7 +106,7 @@ CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent
connect(ui.neutralXSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles()));
connect(ui.neutralYSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles()));
connect(ui.neutralZSpinBox,SIGNAL(editingFinished()),this,SLOT(updateNeutralAngles()));
initConnections();
}
void CameraGimbalConfig::updateRetractAngles()
......
......@@ -39,6 +39,7 @@ CompassConfig::CompassConfig(QWidget *parent) : AP2ConfigWidget(parent)
ui.orientationComboBox->addItem("ROTATION_PITCH_90");
ui.orientationComboBox->addItem("ROTATION_PITCH_270");
ui.orientationComboBox->addItem("ROTATION_MAX");
initConnections();
}
CompassConfig::~CompassConfig()
{
......
......@@ -82,6 +82,12 @@ FailSafeConfig::FailSafeConfig(QWidget *parent) : AP2ConfigWidget(parent)
connect(ui.throttleCheckBox,SIGNAL(clicked(bool)),this,SLOT(throttleChecked(bool)));
connect(ui.throttlePwmSpinBox,SIGNAL(editingFinished()),this,SLOT(throttlePwmChanged()));
connect(ui.throttleFailSafeComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(throttleFailSafeChanged(int)));
ui.armedLabel->setText("<h1>DISARMED</h1>");
ui.modeLabel->setText("<h1>MODE</h1>");
initConnections();
}
void FailSafeConfig::gcsChecked(bool checked)
{
......@@ -224,6 +230,7 @@ void FailSafeConfig::activeUASSet(UASInterface *uas)
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float)));
connect(m_uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)));
connect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
connect(m_uas,SIGNAL(gpsLocalizationChanged(UASInterface*,int)),this,SLOT(gpsStatusChanged(UASInterface*,int)));
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
ui.batteryFailCheckBox->setVisible(false);
......@@ -416,3 +423,18 @@ void FailSafeConfig::hilActuatorsChanged(uint64_t time, float act1, float act2,
ui.radio7Out->setValue(act7);
ui.radio8Out->setValue(act8);
}
void FailSafeConfig::gpsStatusChanged(UASInterface* uas,int fixtype)
{
if (fixtype == 0 || fixtype == 1)
{
ui.gpsLabel->setText("<h1>None</h1>");
}
else if (fixtype == 2)
{
ui.gpsLabel->setText("<h1>2D Fix</h1>");
}
else if (fixtype == 3)
{
ui.gpsLabel->setText("<h1>3D Fix</h1>");
}
}
......@@ -25,6 +25,7 @@ private slots:
void throttleChecked(bool checked);
void throttlePwmChanged();
void throttleFailSafeChanged(int index);
void gpsStatusChanged(UASInterface* uas,int fixtype);
private:
Ui::FailSafeConfig ui;
};
......
......@@ -5,6 +5,7 @@ FlightModeConfig::FlightModeConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.savePushButton,SIGNAL(clicked()),this,SLOT(saveButtonClicked()));
initConnections();
}
FlightModeConfig::~FlightModeConfig()
......
......@@ -44,6 +44,7 @@ FrameTypeConfig::FrameTypeConfig(QWidget *parent) : AP2ConfigWidget(parent)
connect(ui.plusRadioButton,SIGNAL(clicked()),this,SLOT(plusFrameSelected()));
connect(ui.xRadioButton,SIGNAL(clicked()),this,SLOT(xFrameSelected()));
connect(ui.vRadioButton,SIGNAL(clicked()),this,SLOT(vFrameSelected()));
initConnections();
}
FrameTypeConfig::~FrameTypeConfig()
......
......@@ -5,6 +5,7 @@ OpticalFlowConfig::OpticalFlowConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.enableCheckBox,SIGNAL(clicked(bool)),this,SLOT(enableCheckBoxClicked(bool)));
initConnections();
}
OpticalFlowConfig::~OpticalFlowConfig()
......
......@@ -5,6 +5,8 @@ OsdConfig::OsdConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.enablePushButton,SIGNAL(clicked()),this,SLOT(enableButtonClicked()));
initConnections();
}
OsdConfig::~OsdConfig()
......@@ -25,13 +27,4 @@ void OsdConfig::enableButtonClicked()
m_uas->getParamManager()->setParameter(1,"SR0_RAW_CTRL",2);
m_uas->getParamManager()->setParameter(1,"SR0_RAW_SENS",2);
m_uas->getParamManager()->setParameter(1,"SR0_RC_CHAN",2);
m_uas->getParamManager()->setParameter(1,"SR3_EXT_STAT",2);
m_uas->getParamManager()->setParameter(1,"SR3_EXTRA1",10);
m_uas->getParamManager()->setParameter(1,"SR3_EXTRA2",10);
m_uas->getParamManager()->setParameter(1,"SR3_EXTRA3",2);
m_uas->getParamManager()->setParameter(1,"SR3_POSITION",3);
m_uas->getParamManager()->setParameter(1,"SR3_RAW_CTRL",2);
m_uas->getParamManager()->setParameter(1,"SR3_RAW_SENS",2);
m_uas->getParamManager()->setParameter(1,"SR3_RC_CHAN",2);
}
#include "ParamWidget.h"
ParamWidget::ParamWidget(QWidget *parent) : QWidget(parent)
ParamWidget::ParamWidget(QString param,QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
m_param = param;
connect(ui.doubleSpinBox,SIGNAL(editingFinished()),this,SLOT(doubleSpinEditFinished()));
connect(ui.intSpinBox,SIGNAL(editingFinished()),this,SLOT(intSpinEditFinished()));
connect(ui.valueComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(comboIndexChanged(int)));
connect(ui.valueSlider,SIGNAL(sliderReleased()),this,SLOT(valueSliderReleased()));
}
void ParamWidget::doubleSpinEditFinished()
{
ui.valueSlider->setValue(((ui.doubleSpinBox->value() - m_min) / (m_max - m_min)) * 100.0);
emit doubleValueChanged(m_param,ui.doubleSpinBox->value());
}
void ParamWidget::intSpinEditFinished()
{
ui.valueSlider->setValue(((ui.intSpinBox->value() - m_min) / (m_max - m_min)) * 100.0);
emit intValueChanged(m_param,ui.intSpinBox->value());
}
void ParamWidget::comboIndexChanged(int index)
{
emit intValueChanged(m_param,m_valueList[index].first);
}
void ParamWidget::valueSliderReleased()
{
//Set the spin box, and emit a signal.
if (type == INT)
{
ui.intSpinBox->setValue(((ui.valueSlider->value() / 100.0) * (m_max - m_min)) + m_min);
emit intValueChanged(m_param,ui.intSpinBox->value());
}
else if (type == DOUBLE)
{
ui.doubleSpinBox->setValue(((ui.valueSlider->value() / 100.0) * (m_max - m_min)) + m_min);
emit doubleValueChanged(m_param,ui.doubleSpinBox->value());
}
}
ParamWidget::~ParamWidget()
......@@ -19,8 +55,18 @@ void ParamWidget::setupInt(QString title,QString description,int value,int min,i
ui.valueSlider->show();
ui.intSpinBox->show();
ui.doubleSpinBox->hide();
m_min = min;
m_max = max;
if (min == 0 && max == 0)
{
m_min = 0;
m_max = 65535;
}
else
{
m_min = min;
m_max = max;
}
ui.intSpinBox->setMinimum(m_min);
ui.intSpinBox->setMaximum(m_max);
}
void ParamWidget::setupDouble(QString title,QString description,double value,double min,double max)
......@@ -32,8 +78,18 @@ void ParamWidget::setupDouble(QString title,QString description,double value,dou
ui.valueSlider->show();
ui.intSpinBox->hide();
ui.doubleSpinBox->show();
m_min = min;
m_max = max;
if (min == 0 && max == 0)
{
m_min = 0;
m_max = 65535;
}
else
{
m_min = min;
m_max = max;
}
ui.doubleSpinBox->setMinimum(m_min);
ui.doubleSpinBox->setMaximum(m_max);
}
void ParamWidget::setupCombo(QString title,QString description,QList<QPair<int,QString> > list)
......@@ -47,10 +103,12 @@ void ParamWidget::setupCombo(QString title,QString description,QList<QPair<int,Q
ui.doubleSpinBox->hide();
m_valueList = list;
ui.valueComboBox->clear();
disconnect(ui.valueComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(comboIndexChanged(int)));
for (int i=0;i<m_valueList.size();i++)
{
ui.valueComboBox->addItem(m_valueList[i].second);
}
connect(ui.valueComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(comboIndexChanged(int)));
}
void ParamWidget::setValue(double value)
......@@ -58,12 +116,12 @@ void ParamWidget::setValue(double value)
if (type == INT)
{
ui.intSpinBox->setValue(value);
ui.valueSlider->setValue(((value + m_min) / (m_max + m_min)) * 100.0);
ui.valueSlider->setValue(((value - m_min) / (m_max - m_min)) * 100.0);
}
else if (type == DOUBLE)
{
ui.doubleSpinBox->setValue(value);
ui.valueSlider->setValue(((value + m_min) / (m_max + m_min)) * 100.0);
ui.valueSlider->setValue(((value - m_min) / (m_max - m_min)) * 100.0);
}
else if (type == COMBO)
{
......@@ -71,7 +129,9 @@ void ParamWidget::setValue(double value)
{
if ((int)value == m_valueList[i].first)
{
disconnect(ui.valueComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(comboIndexChanged(int)));
ui.valueComboBox->setCurrentIndex(i);
connect(ui.valueComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(comboIndexChanged(int)));
return;
}
}
......
......@@ -9,13 +9,22 @@ class ParamWidget : public QWidget
Q_OBJECT
public:
explicit ParamWidget(QWidget *parent = 0);
explicit ParamWidget(QString param,QWidget *parent = 0);
~ParamWidget();
void setupInt(QString title,QString description,int value,int min,int max);
void setupDouble(QString title,QString description,double value,double min,double max);
void setupCombo(QString title,QString description,QList<QPair<int,QString> > list);
void setValue(double value);
signals:
void doubleValueChanged(QString param,double value);
void intValueChanged(QString param,int value);
private slots:
void doubleSpinEditFinished();
void intSpinEditFinished();
void comboIndexChanged(int index);
void valueSliderReleased();
private:
QString m_param;
enum VIEWTYPE
{
INT,
......
......@@ -46,6 +46,9 @@
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
......
......@@ -71,6 +71,13 @@ RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : AP2ConfigWidge
guiUpdateTimer = new QTimer(this);
connect(guiUpdateTimer,SIGNAL(timeout()),this,SLOT(guiUpdateTimerTick()));
rcMin << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0 << 1100.0;
rcMax << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0 << 1900.0;
rcTrim << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0 << 1500.0;
rcValue << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0 << 0.0;
initConnections();
}
RadioCalibrationConfig::~RadioCalibrationConfig()
......@@ -170,6 +177,7 @@ void RadioCalibrationConfig::calibrateButtonClicked()
ui.radio5Widget->showMinMax();
ui.radio6Widget->showMinMax();
ui.radio7Widget->showMinMax();
ui.throttleWidget->showMinMax();
ui.radio8Widget->showMinMax();
QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
}
......@@ -184,6 +192,7 @@ void RadioCalibrationConfig::calibrateButtonClicked()
ui.yawWidget->hideMinMax();
ui.radio5Widget->hideMinMax();
ui.radio6Widget->hideMinMax();
ui.throttleWidget->hideMinMax();
ui.radio7Widget->hideMinMax();
ui.radio8Widget->hideMinMax();
QString statusstr;
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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