Browse Source

merged

QGC4.4
dongfang 12 years ago
parent
commit
ccd2ba2f24
  1. 4
      files/styles/style-indoor.css
  2. 4
      files/styles/style-outdoor.css
  3. 2
      src/configuration.h
  4. 7
      src/uas/UAS.cc
  5. 23
      src/ui/DebugConsole.cc
  6. 4
      src/ui/DebugConsole.h
  7. 6
      src/ui/HDDisplay.cc
  8. 2
      src/ui/HSIDisplay.cc
  9. 61
      src/ui/MainWindow.cc
  10. 1
      src/ui/MainWindow.ui
  11. 23
      src/ui/PrimaryFlightDisplay.cpp
  12. 68
      src/ui/QGCVehicleConfig.cc
  13. 9
      src/ui/QGCVehicleConfig.h
  14. 1860
      src/ui/QGCVehicleConfig.ui
  15. 6
      src/ui/QGCWaypointListMulti.cc
  16. 19
      src/ui/uas/UASInfoWidget.cc
  17. 5
      src/ui/uas/UASListWidget.cc

4
files/styles/style-indoor.css

@ -178,8 +178,8 @@ QDoubleSpinBox::down-button { @@ -178,8 +178,8 @@ QDoubleSpinBox::down-button {
}
QPushButton {
min-height: 20px;
max-height: 20px;
/*min-height: 20px;*/
/*max-height: 20px;*/
border: 1px solid #465158;
margin: 1px;
border-radius: 2px;

4
files/styles/style-outdoor.css

@ -184,8 +184,8 @@ QDoubleSpinBox::down-button { @@ -184,8 +184,8 @@ QDoubleSpinBox::down-button {
QPushButton {
font-weight: bold;
min-height: 18px;
max-height: 18px;
/*min-height: 18px;*/
/*max-height: 18px;*/
border: 2px solid #4A4A4F;
border-radius: 5px;
padding-left: 10px;

2
src/configuration.h

@ -11,7 +11,7 @@ @@ -11,7 +11,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 1.0.9 (beta)"
#define QGC_APPLICATION_VERSION "v. 1.0.10 (beta)"
namespace QGC

7
src/uas/UAS.cc

@ -1148,13 +1148,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -1148,13 +1148,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
mavlink_msg_statustext_get_text(&message, b.data());
//b.append('\0');
// Ensure NUL-termination
b[b.length()-1] = '\0';
QString text = QString(b);
int severity = mavlink_msg_statustext_get_severity(&message);
//qDebug() << "RECEIVED STATUS:" << text;false
//emit statusTextReceived(severity, text);
if (text.startsWith("#audio:"))
{

23
src/ui/DebugConsole.cc

@ -93,14 +93,23 @@ DebugConsole::DebugConsole(QWidget *parent) : @@ -93,14 +93,23 @@ DebugConsole::DebugConsole(QWidget *parent) :
// Update measurements the first time
updateTrafficMeasurements();
// First connect management slots, then make sure to add all existing objects
// Connect to link manager to get notified about new links
connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*)));
// Connect to UAS manager to get notified about new UAS
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(uasCreated(UASInterface*)));
// Get a list of all existing links
links = QList<LinkInterface*>();
foreach (LinkInterface* link, LinkManager::instance()->getLinks()) {
addLink(link);
}
// Connect to link manager to get notified about new links
connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*)));
// Get a list of all existing UAS
foreach (UASInterface* uas, UASManager::instance()->getUASList()) {
uasCreated(uas);
}
// Connect link combo box
connect(m_ui->linkComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(linkSelected(int)));
// Connect send button
@ -169,6 +178,12 @@ void DebugConsole::storeSettings() @@ -169,6 +178,12 @@ void DebugConsole::storeSettings()
//qDebug() << "Storing settings!";
}
void DebugConsole::uasCreated(UASInterface* uas)
{
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
this, SLOT(receiveTextMessage(int,int,int,QString)), Qt::UniqueConnection);
}
/**
* Add a link to the debug console output
*/
@ -183,8 +198,8 @@ void DebugConsole::addLink(LinkInterface* link) @@ -183,8 +198,8 @@ void DebugConsole::addLink(LinkInterface* link)
linkSelected(m_ui->linkComboBox->currentIndex());
// Register for name changes
connect(link, SIGNAL(nameChanged(QString)), this, SLOT(updateLinkName(QString)));
connect(link, SIGNAL(deleteLink(LinkInterface* const)), this, SLOT(removeLink(LinkInterface* const)));
connect(link, SIGNAL(nameChanged(QString)), this, SLOT(updateLinkName(QString)), Qt::UniqueConnection);
connect(link, SIGNAL(deleteLink(LinkInterface* const)), this, SLOT(removeLink(LinkInterface* const)), Qt::UniqueConnection);
}
void DebugConsole::removeLink(LinkInterface* const linkInterface)

4
src/ui/DebugConsole.h

@ -45,6 +45,8 @@ namespace Ui @@ -45,6 +45,8 @@ namespace Ui
class DebugConsole;
}
class UASInterface;
/**
* @brief Shows a debug console
*
@ -61,6 +63,8 @@ public: @@ -61,6 +63,8 @@ public:
public slots:
/** @brief Add a link to the list of monitored links */
void addLink(LinkInterface* link);
/** @brief Add a UAS to the list of monitored UAS */
void uasCreated(UASInterface* uas);
/** @brief Remove a link from the list */
void removeLink(LinkInterface* const link);
/** @brief Update a link name */

6
src/ui/HDDisplay.cc

@ -128,8 +128,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) : @@ -128,8 +128,8 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
if (font.family() != fontFamilyName) qDebug() << "ERROR! Font not loaded: " << fontFamilyName;
// Connect with UAS
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
//start();
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
setActiveUAS(UASManager::instance()->getActiveUAS());
}
HDDisplay::~HDDisplay()
@ -476,6 +476,8 @@ void HDDisplay::renderOverlay() @@ -476,6 +476,8 @@ void HDDisplay::renderOverlay()
*/
void HDDisplay::setActiveUAS(UASInterface* uas)
{
if (!uas)
return;
// Disconnect any previously connected active UAS
if (this->uas != NULL) {
removeSource(this->uas);

2
src/ui/HSIDisplay.cc

@ -178,6 +178,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) : @@ -178,6 +178,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
connect(&statusClearTimer, SIGNAL(timeout()), this, SLOT(clearStatusMessage()));
statusClearTimer.start(3000);
setActiveUAS(UASManager::instance()->getActiveUAS());
setFocusPolicy(Qt::StrongFocus);
}

61
src/ui/MainWindow.cc

@ -1730,43 +1730,17 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1730,43 +1730,17 @@ void MainWindow::UASCreated(UASInterface* uas)
break;
}
// XXX The multi-UAS selection menu has been disabled for now,
// its redundant with right-clicking the UAS in the list.
// this code piece might be removed later if this is the final
// conclusion (May 2013)
// QAction* uasAction = new QAction(icon, tr("Select %1 for control").arg(uas->getUASName()), ui.menuConnected_Systems);
// connect(uas, SIGNAL(systemRemoved()), uasAction, SLOT(deleteLater()));
// connect(uasAction, SIGNAL(triggered()), uas, SLOT(setSelected()));
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int)));
// ui.menuConnected_Systems->addAction(uasAction);
// FIXME Should be not inside the mainwindow
if (debugConsoleDockWidget)
{
DebugConsole *debugConsole = dynamic_cast<DebugConsole*>(debugConsoleDockWidget->widget());
if (debugConsole)
{
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)),
debugConsole, SLOT(receiveTextMessage(int,int,int,QString)));
}
}
// Health / System status indicator
if (infoDockWidget)
{
UASInfoWidget *infoWidget = dynamic_cast<UASInfoWidget*>(infoDockWidget->widget());
if (infoWidget)
{
infoWidget->addUAS(uas);
}
}
// UAS List
if (listDockWidget)
{
UASListWidget *listWidget = dynamic_cast<UASListWidget*>(listDockWidget->widget());
if (listWidget)
{
listWidget->addUAS(uas);
}
}
connect(uas, SIGNAL(systemSpecsChanged(int)), this, SLOT(UASSpecsChanged(int)));
// HIL
showHILConfigurationWidget(uas);
@ -1778,25 +1752,12 @@ void MainWindow::UASCreated(UASInterface* uas) @@ -1778,25 +1752,12 @@ void MainWindow::UASCreated(UASInterface* uas)
}
// Line chart
//if (!linechartWidget)
//{
// Center widgets
//linechartWidget->addSystem(uas);
linechartWidget->addSource(mavlinkDecoder);
//addCentralWidget(linechartWidget, tr("Realtime Plot"));
if (dataView->centralWidget() != linechartWidget)
{
dataView->setCentralWidget(linechartWidget);
linechartWidget->show();
}
//dataView->setCentralWidget(linechartWidget);
//linechartWidget->show();
//}
linechartWidget->addSource(mavlinkDecoder);
if (dataView->centralWidget() != linechartWidget)
{
dataView->setCentralWidget(linechartWidget);
linechartWidget->show();
}
// Load default custom widgets for this autopilot type
loadCustomWidgetsFromDefaults(uas->getSystemTypeName(), uas->getAutopilotTypeName());

1
src/ui/MainWindow.ui

@ -89,6 +89,7 @@ @@ -89,6 +89,7 @@
</property>
<addaction name="actionNewCustomWidget"/>
<addaction name="actionLoadCustomWidgetFile"/>
<addaction name="separator"/>
</widget>
<widget class="QMenu" name="menuHelp">
<property name="title">

23
src/ui/PrimaryFlightDisplay.cpp

@ -9,7 +9,8 @@ @@ -9,7 +9,8 @@
#include <QPainter>
#include <QPainterPath>
#include <QResizeEvent>
#include <math.h>
//#include <math.h>
#include <cmath>
/*
*@TODO:
@ -17,6 +18,10 @@ @@ -17,6 +18,10 @@
* repaint on demand multiple canvases
* multi implementation with shared model class
*/
double round(double value, int digits=0)
{
return floor(value * pow(10, digits) + 0.5) / pow(10, digits);
}
const int PrimaryFlightDisplay::tickValues[] = {10, 20, 30, 45, 60};
const QString PrimaryFlightDisplay::compassWindNames[] = {
@ -35,7 +40,8 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren @@ -35,7 +40,8 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren
roll(0),
pitch(0),
heading(NAN),
// heading(NAN),
heading(0),
aboveASLAltitude(0),
GPSAltitude(0),
aboveHomeAltitude(0),
@ -80,7 +86,8 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren @@ -80,7 +86,8 @@ PrimaryFlightDisplay::PrimaryFlightDisplay(int width, int height, QWidget *paren
// Refresh timer
refreshTimer->setInterval(updateInterval);
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
// connect(refreshTimer, SIGNAL(timeout()), this, SLOT(paintHUD()));
connect(refreshTimer, SIGNAL(timeout()), this, SLOT(update()));
}
PrimaryFlightDisplay::~PrimaryFlightDisplay()
@ -165,9 +172,9 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double @@ -165,9 +172,9 @@ void PrimaryFlightDisplay::updateAttitude(UASInterface* uas, double roll, double
if (!isnan(roll) && !isinf(roll) && !isnan(pitch) && !isinf(pitch) && !isnan(yaw) && !isinf(yaw))
{
// TODO: Units conversion?
this->roll = roll;
this->pitch = pitch;
this->heading = yaw;
this->roll = roll * (180.0 / M_PI);
this->pitch = pitch * (180.0 / M_PI);
this->heading = yaw * (180.0 / M_PI);
}
// TODO: Else-part. We really should have an "attitude bad or unknown" indication instead of just freezing.
@ -309,7 +316,7 @@ void PrimaryFlightDisplay::paintEvent(QPaintEvent *event) @@ -309,7 +316,7 @@ void PrimaryFlightDisplay::paintEvent(QPaintEvent *event)
// the event is ignored as this widget
// is refreshed automatically
Q_UNUSED(event);
makeDummyData();
//makeDummyData();
doPaint();
}
@ -319,7 +326,7 @@ void PrimaryFlightDisplay::paintOnTimer() { @@ -319,7 +326,7 @@ void PrimaryFlightDisplay::paintOnTimer() {
*The whole tainted-flag shebang.
*well not really so critical. Worst problem is deletion?
*/
makeDummyData();
//makeDummyData();
doPaint();
}

68
src/ui/QGCVehicleConfig.cc

@ -44,6 +44,12 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : @@ -44,6 +44,12 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
setObjectName("QGC_VEHICLECONFIG");
ui->setupUi(this);
connect(ui->rcMenuButton,SIGNAL(clicked()),this,SLOT(rcMenuButtonClicked()));
connect(ui->sensorMenuButton,SIGNAL(clicked()),this,SLOT(sensorMenuButtonClicked()));
connect(ui->generalMenuButton,SIGNAL(clicked()),this,SLOT(generalMenuButtonClicked()));
connect(ui->advancedMenuButton,SIGNAL(clicked()),this,SLOT(advancedMenuButtonClicked()));
requestCalibrationRC();
if (mav) mav->requestParameter(0, "RC_TYPE");
@ -89,6 +95,25 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : @@ -89,6 +95,25 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateView()));
updateTimer.start();
}
void QGCVehicleConfig::rcMenuButtonClicked()
{
ui->stackedWidget->setCurrentIndex(0);
}
void QGCVehicleConfig::sensorMenuButtonClicked()
{
ui->stackedWidget->setCurrentIndex(1);
}
void QGCVehicleConfig::generalMenuButtonClicked()
{
ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-2);
}
void QGCVehicleConfig::advancedMenuButtonClicked()
{
ui->stackedWidget->setCurrentIndex(ui->stackedWidget->count()-1);
}
QGCVehicleConfig::~QGCVehicleConfig()
{
@ -247,8 +272,18 @@ void QGCVehicleConfig::loadQgcConfig(bool primary) @@ -247,8 +272,18 @@ void QGCVehicleConfig::loadQgcConfig(bool primary)
//Load tabs for general configuration
foreach (QString dir,generaldir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
{
QWidget *tab = new QWidget(ui->tabWidget);
ui->tabWidget->insertTab(2,tab,dir);
QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3);
connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
ui->navBarLayout->insertWidget(2,button);
button->setMinimumHeight(100);
button->setMinimumWidth(100);
button->show();
button->setText(dir);
//QWidget *tab = new QWidget(ui->tabWidget);
//ui->tabWidget->insertTab(2,tab,dir);
QWidget *tab = new QWidget(ui->stackedWidget);
ui->stackedWidget->insertWidget(2,tab);
buttonToWidgetMap[button] = tab;
tab->setLayout(new QVBoxLayout());
tab->show();
QScrollArea *area = new QScrollArea();
@ -283,8 +318,20 @@ void QGCVehicleConfig::loadQgcConfig(bool primary) @@ -283,8 +318,20 @@ void QGCVehicleConfig::loadQgcConfig(bool primary)
//Load tabs for vehicle specific configuration
foreach (QString dir,vehicledir.entryList(QDir::Dirs | QDir::NoDotAndDotDot))
{
QWidget *tab = new QWidget(ui->tabWidget);
ui->tabWidget->insertTab(2,tab,dir);
//QWidget *tab = new QWidget(ui->tabWidget);
//ui->tabWidget->insertTab(2,tab,dir);
QPushButton *button = new QPushButton(ui->scrollAreaWidgetContents_3);
connect(button,SIGNAL(clicked()),this,SLOT(menuButtonClicked()));
ui->navBarLayout->insertWidget(2,button);
QWidget *tab = new QWidget(ui->stackedWidget);
ui->stackedWidget->insertWidget(2,tab);
buttonToWidgetMap[button] = tab;
button->setMinimumHeight(100);
button->setMinimumWidth(100);
button->show();
button->setText(dir);
tab->setLayout(new QVBoxLayout());
tab->show();
QScrollArea *area = new QScrollArea();
@ -362,6 +409,19 @@ void QGCVehicleConfig::loadQgcConfig(bool primary) @@ -362,6 +409,19 @@ void QGCVehicleConfig::loadQgcConfig(bool primary)
}
void QGCVehicleConfig::menuButtonClicked()
{
QPushButton *button = qobject_cast<QPushButton*>(sender());
if (!button)
{
return;
}
if (buttonToWidgetMap.contains(button))
{
ui->stackedWidget->setCurrentWidget(buttonToWidgetMap[button]);
}
}
void QGCVehicleConfig::loadConfig()
{

9
src/ui/QGCVehicleConfig.h

@ -5,6 +5,7 @@ @@ -5,6 +5,7 @@
#include <QTimer>
#include <QList>
#include <QGroupBox>
#include <QPushButton>
#include "QGCToolWidget.h"
#include "UASInterface.h"
@ -29,6 +30,11 @@ public: @@ -29,6 +30,11 @@ public:
};
public slots:
void rcMenuButtonClicked();
void sensorMenuButtonClicked();
void generalMenuButtonClicked();
void advancedMenuButtonClicked();
/** Set the MAV currently being calibrated */
void setActiveUAS(UASInterface* active);
/** Fallback function, automatically called by loadConfig() upon failure to find and xml file*/
@ -125,6 +131,7 @@ public slots: @@ -125,6 +131,7 @@ public slots:
}
protected slots:
void menuButtonClicked();
/** Reset the RC calibration */
void resetCalibrationRC();
/** Write the RC calibration */
@ -183,7 +190,7 @@ protected: @@ -183,7 +190,7 @@ protected:
private:
Ui::QGCVehicleConfig *ui;
QMap<QPushButton*,QWidget*> buttonToWidgetMap;
signals:
void visibilityChanged(bool visible);
};

1860
src/ui/QGCVehicleConfig.ui

File diff suppressed because it is too large Load Diff

6
src/ui/QGCWaypointListMulti.cc

@ -15,6 +15,12 @@ QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) : @@ -15,6 +15,12 @@ QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) :
WaypointList* list = new WaypointList(ui->stackedWidget, NULL);
lists.insert(offline_uas_id, list);
ui->stackedWidget->addWidget(list);
if (UASManager::instance()->getActiveUAS()) {
systemCreated(UASManager::instance()->getActiveUAS());
systemSetActive(UASManager::instance()->getActiveUAS()->getUASID());
}
}
void QGCWaypointListMulti::systemDeleted(QObject* uas)

19
src/ui/uas/UASInfoWidget.cc

@ -34,7 +34,7 @@ This file is part of the PIXHAWK project @@ -34,7 +34,7 @@ This file is part of the PIXHAWK project
#include <float.h>
#include <UASInfoWidget.h>
#include <UASManager.h>
#include <MG.h>
#include <QGC.h>
#include <QTimer>
#include <QDir>
#include <cstdlib>
@ -46,20 +46,12 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent) @@ -46,20 +46,12 @@ UASInfoWidget::UASInfoWidget(QWidget *parent, QString name) : QWidget(parent)
{
ui.setupUi(this);
this->name = name;
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
activeUAS = NULL;
//instruments = new QMap<QString, QProgressBar*>();
// Set default battery type
// setBattery(0, LIPOLY, 3);
startTime = MG::TIME::getGroundTimeNow();
// startVoltage = 0.0f;
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
setActiveUAS(UASManager::instance()->getActiveUAS());
// lastChargeLevel = 0.5f;
// lastRemainingTime = 1;
startTime = QGC::groundTimeMilliseconds();
// Set default values
/** Set two voltage decimals and zero charge level decimals **/
@ -117,7 +109,8 @@ void UASInfoWidget::addUAS(UASInterface* uas) @@ -117,7 +109,8 @@ void UASInfoWidget::addUAS(UASInterface* uas)
void UASInfoWidget::setActiveUAS(UASInterface* uas)
{
activeUAS = uas;
if (uas)
activeUAS = uas;
}
void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double percent, int seconds)

5
src/ui/uas/UASListWidget.cc

@ -67,6 +67,11 @@ UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent), m_ui(new Ui::UA @@ -67,6 +67,11 @@ UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent), m_ui(new Ui::UA
this->setVisible(false);
connect(UASManager::instance(),SIGNAL(UASCreated(UASInterface*)),this,SLOT(addUAS(UASInterface*)));
// Get a list of all existing UAS
foreach (UASInterface* uas, UASManager::instance()->getUASList()) {
addUAS(uas);
}
}
UASListWidget::~UASListWidget()

Loading…
Cancel
Save