Browse Source

white space

QGC4.4
Alejandro 14 years ago
parent
commit
ed323bbebd
  1. 2142
      src/lib/qextserialport/win_qextserialport.cpp
  2. 3652
      src/uas/UAS.cc
  3. 504
      src/uas/UASManager.cc
  4. 3819
      src/ui/MainWindow.cc
  5. 970
      src/ui/WaypointList.cc
  6. 278
      src/ui/designer/QGCActionButton.cc
  7. 1252
      src/ui/uas/UASView.cc

2142
src/lib/qextserialport/win_qextserialport.cpp

File diff suppressed because it is too large Load Diff

3652
src/uas/UAS.cc

File diff suppressed because it is too large Load Diff

504
src/uas/UASManager.cc

@ -1,252 +1,252 @@ @@ -1,252 +1,252 @@
/*=====================================================================
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 class UASManager
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QApplication>
#include <QMessageBox>
#include <QTimer>
#include "UAS.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "QGC.h"
UASManager* UASManager::instance()
{
static UASManager* _instance = 0;
if(_instance == 0) {
_instance = new UASManager();
// Set the application as parent to ensure that this object
// will be destroyed when the main application exits
_instance->setParent(qApp);
}
return _instance;
}
/**
* @brief Private singleton constructor
*
* This class implements the singleton design pattern and has therefore only a private constructor.
**/
UASManager::UASManager() :
activeUAS(NULL)
{
systems = QList<UASInterface*>();
start(QThread::LowPriority);
}
UASManager::~UASManager()
{
}
void UASManager::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
void UASManager::addUAS(UASInterface* uas)
{
// WARNING: The active uas is set here
// and then announced below. This is necessary
// to make sure the getActiveUAS() function
// returns the UAS once the UASCreated() signal
// is emitted. The code is thus NOT redundant.
bool firstUAS = false;
if (activeUAS == NULL)
{
firstUAS = true;
activeUAS = uas;
}
// Only execute if there is no UAS at this index
if (!systems.contains(uas))
{
systems.append(uas);
connect(uas, SIGNAL(destroyed(QObject*)), this, SLOT(removeUAS(QObject*)));
emit UASCreated(uas);
}
// If there is no active UAS yet, set the first one as the active UAS
if (firstUAS)
{
setActiveUAS(uas);
}
}
void UASManager::removeUAS(QObject* uas)
{
UASInterface* mav = qobject_cast<UASInterface*>(uas);
if (mav)
{
int listindex = systems.indexOf(mav);
if (mav == activeUAS)
{
if (systems.count() > 1)
{
// We only set a new UAS if more than one is present
if (listindex != 0)
{
// The system to be removed is not at position 1
// set position one as new active system
setActiveUAS(systems.first());
}
else
{
// The system to be removed is at position 1,
// select the next system
setActiveUAS(systems.at(1));
}
}
else
{
// TODO send a null pointer if no UAS is present any more
// This has to be proberly tested however, since it might
// crash code parts not handling null pointers correctly.
}
}
systems.removeAt(listindex);
}
}
QList<UASInterface*> UASManager::getUASList()
{
return systems;
}
UASInterface* UASManager::getActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASInterface* UASManager::silentGetActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->launch();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::haltActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->halt();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::continueActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->go();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::returnActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->home();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::stopActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->emergencySTOP();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::killActiveUAS()
{
if (getActiveUAS()) activeUAS->emergencyKILL();
return (activeUAS);
}
bool UASManager::shutdownActiveUAS()
{
if (getActiveUAS()) activeUAS->shutdown();
return (activeUAS);
}
void UASManager::configureActiveUAS()
{
UASInterface* actUAS = getActiveUAS();
if(actUAS)
{
// Do something
}
}
UASInterface* UASManager::getUASForId(int id)
{
UASInterface* system = NULL;
foreach(UASInterface* sys, systems)
{
if (sys->getUASID() == id)
{
system = sys;
}
}
// Return NULL if not found
return system;
}
void UASManager::setActiveUAS(UASInterface* uas)
{
if (uas != NULL)
{
activeUASMutex.lock();
if (activeUAS != NULL)
{
emit activeUASStatusChanged(activeUAS, false);
emit activeUASStatusChanged(activeUAS->getUASID(), false);
}
activeUAS = uas;
activeUASMutex.unlock();
activeUAS->setSelected();
emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
emit activeUASSetListIndex(systems.indexOf(uas));
emit activeUASStatusChanged(uas, true);
emit activeUASStatusChanged(uas->getUASID(), true);
}
}
/*=====================================================================
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 class UASManager
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QList>
#include <QApplication>
#include <QMessageBox>
#include <QTimer>
#include "UAS.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "QGC.h"
UASManager* UASManager::instance()
{
static UASManager* _instance = 0;
if(_instance == 0) {
_instance = new UASManager();
// Set the application as parent to ensure that this object
// will be destroyed when the main application exits
_instance->setParent(qApp);
}
return _instance;
}
/**
* @brief Private singleton constructor
*
* This class implements the singleton design pattern and has therefore only a private constructor.
**/
UASManager::UASManager() :
activeUAS(NULL)
{
systems = QList<UASInterface*>();
start(QThread::LowPriority);
}
UASManager::~UASManager()
{
}
void UASManager::run()
{
forever
{
QGC::SLEEP::msleep(5000);
}
}
void UASManager::addUAS(UASInterface* uas)
{
// WARNING: The active uas is set here
// and then announced below. This is necessary
// to make sure the getActiveUAS() function
// returns the UAS once the UASCreated() signal
// is emitted. The code is thus NOT redundant.
bool firstUAS = false;
if (activeUAS == NULL)
{
firstUAS = true;
activeUAS = uas;
}
// Only execute if there is no UAS at this index
if (!systems.contains(uas))
{
systems.append(uas);
connect(uas, SIGNAL(destroyed(QObject*)), this, SLOT(removeUAS(QObject*)));
emit UASCreated(uas);
}
// If there is no active UAS yet, set the first one as the active UAS
if (firstUAS)
{
setActiveUAS(uas);
}
}
void UASManager::removeUAS(QObject* uas)
{
UASInterface* mav = qobject_cast<UASInterface*>(uas);
if (mav)
{
int listindex = systems.indexOf(mav);
if (mav == activeUAS)
{
if (systems.count() > 1)
{
// We only set a new UAS if more than one is present
if (listindex != 0)
{
// The system to be removed is not at position 1
// set position one as new active system
setActiveUAS(systems.first());
}
else
{
// The system to be removed is at position 1,
// select the next system
setActiveUAS(systems.at(1));
}
}
else
{
// TODO send a null pointer if no UAS is present any more
// This has to be proberly tested however, since it might
// crash code parts not handling null pointers correctly.
}
}
systems.removeAt(listindex);
}
}
QList<UASInterface*> UASManager::getUASList()
{
return systems;
}
UASInterface* UASManager::getActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
UASInterface* UASManager::silentGetActiveUAS()
{
return activeUAS; ///< Return zero pointer if no UAS has been loaded
}
bool UASManager::launchActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->launch();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::haltActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->halt();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::continueActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->go();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::returnActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->home();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::stopActiveUAS()
{
// If the active UAS is set, execute command
if (getActiveUAS()) activeUAS->emergencySTOP();
return (activeUAS); ///< Returns true if the UAS exists, false else
}
bool UASManager::killActiveUAS()
{
if (getActiveUAS()) activeUAS->emergencyKILL();
return (activeUAS);
}
bool UASManager::shutdownActiveUAS()
{
if (getActiveUAS()) activeUAS->shutdown();
return (activeUAS);
}
void UASManager::configureActiveUAS()
{
UASInterface* actUAS = getActiveUAS();
if(actUAS)
{
// Do something
}
}
UASInterface* UASManager::getUASForId(int id)
{
UASInterface* system = NULL;
foreach(UASInterface* sys, systems)
{
if (sys->getUASID() == id)
{
system = sys;
}
}
// Return NULL if not found
return system;
}
void UASManager::setActiveUAS(UASInterface* uas)
{
if (uas != NULL)
{
activeUASMutex.lock();
if (activeUAS != NULL)
{
emit activeUASStatusChanged(activeUAS, false);
emit activeUASStatusChanged(activeUAS->getUASID(), false);
}
activeUAS = uas;
activeUASMutex.unlock();
activeUAS->setSelected();
emit activeUASSet(uas);
emit activeUASSet(uas->getUASID());
emit activeUASSetListIndex(systems.indexOf(uas));
emit activeUASStatusChanged(uas, true);
emit activeUASStatusChanged(uas->getUASID(), true);
}
}

3819
src/ui/MainWindow.cc

File diff suppressed because it is too large Load Diff

970
src/ui/WaypointList.cc

@ -1,485 +1,485 @@ @@ -1,485 +1,485 @@
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK 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.
PIXHAWK 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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Waypoint list widget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include "WaypointList.h"
#include "ui_WaypointList.h"
#include <UASInterface.h>
#include <UASManager.h>
#include <QDebug>
#include <QFileDialog>
#include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent),
uas(NULL),
mavX(0.0),
mavY(0.0),
mavZ(0.0),
mavYaw(0.0),
m_ui(new Ui::WaypointList)
{
m_ui->setupUi(this);
listLayout = new QVBoxLayout(m_ui->listWidget);
listLayout->setSpacing(6);
listLayout->setMargin(0);
listLayout->setAlignment(Qt::AlignTop);
m_ui->listWidget->setLayout(listLayout);
// ADD WAYPOINT
// Connect add action, set right button icon and connect action to this class
connect(m_ui->addButton, SIGNAL(clicked()), m_ui->actionAddWaypoint, SIGNAL(triggered()));
connect(m_ui->actionAddWaypoint, SIGNAL(triggered()), this, SLOT(add()));
// ADD WAYPOINT AT CURRENT POSITION
connect(m_ui->positionAddButton, SIGNAL(clicked()), this, SLOT(addCurrentPositonWaypoint()));
// SEND WAYPOINTS
connect(m_ui->transmitButton, SIGNAL(clicked()), this, SLOT(transmit()));
// REQUEST WAYPOINTS
connect(m_ui->readButton, SIGNAL(clicked()), this, SLOT(read()));
// SAVE/LOAD WAYPOINTS
connect(m_ui->saveButton, SIGNAL(clicked()), this, SLOT(saveWaypoints()));
connect(m_ui->loadButton, SIGNAL(clicked()), this, SLOT(loadWaypoints()));
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
setUAS(uas);
// STATUS LABEL
updateStatusLabel("");
this->setVisible(false);
loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
}
WaypointList::~WaypointList()
{
delete m_ui;
}
void WaypointList::updatePosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
mavX = x;
mavY = y;
mavZ = z;
}
void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
Q_UNUSED(roll);
Q_UNUSED(pitch);
mavYaw = yaw;
}
void WaypointList::setUAS(UASInterface* uas)
{
if (this->uas == NULL && uas != NULL)
{
this->uas = uas;
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int,Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
void WaypointList::saveWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
uas->getWaypointManager()->saveWaypoints(fileName);
}
}
void WaypointList::loadWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager()->loadWaypoints(fileName);
}
}
void WaypointList::transmit()
{
if (uas)
{
uas->getWaypointManager()->writeWaypoints();
}
}
void WaypointList::read()
{
if (uas)
{
uas->getWaypointManager()->readWaypoints();
}
}
void WaypointList::add()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
Waypoint *wp;
if (waypoints.size() > 0)
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(),
last->getHoldTime(), last->getFrame(), last->getAction());
uas->getWaypointManager()->addWaypoint(wp);
}
else
{
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLongitude(), uas->getLatitude(), uas->getAltitude(), 0.0, true, true, 0.15, 0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE);
uas->getWaypointManager()->addWaypoint(wp);
}
// if (wp->getFrame() == MAV_FRAME_GLOBAL)
// {
// emit createWaypointAtMap(QPointF(wp->getX(), wp->getY()));
// }
}
}
void WaypointList::addCurrentPositonWaypoint()
{
/* TODO: implement with new waypoint structure
if (uas)
{
// For Global Waypoints
//if(isGlobalWP)
//{
//isLocalWP = false;
//}
//else
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager()->addWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager()->addWaypoint(wp);
}
//isLocalWP = true;
}
}
*/
}
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
{
if (uas)
{
uas->getWaypointManager()->setCurrentWaypoint(seq);
}
}
void WaypointList::currentWaypointChanged(quint16 seq)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
widget->setCurrent(true);
}
else
{
widget->setCurrent(false);
}
}
}
}
}
void WaypointList::updateWaypoint(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues();
}
void WaypointList::waypointListChanged()
{
if (uas)
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
this->setUpdatesEnabled(true);
}
loadFileGlobalWP = false;
}
void WaypointList::moveUp(Waypoint* wp)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the first entry, move it
if (i < waypoints.size() && i > 0)
{
uas->getWaypointManager()->moveWaypoint(i, i-1);
}
}
//emitir señal de cambio orden en la lista,
//la debe capturar el mapwidget para volver a dibujar la ruta
}
void WaypointList::moveDown(Waypoint* wp)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the last entry, move it
if (i < waypoints.size()-1)
{
uas->getWaypointManager()->moveWaypoint(i, i+1);
}
}
}
void WaypointList::removeWaypoint(Waypoint* wp)
{
if (uas)
{
uas->getWaypointManager()->removeWaypoint(wp->getId());
}
}
void WaypointList::changeEvent(QEvent *e)
{
switch (e->type()) {
case QEvent::LanguageChange:
m_ui->retranslateUi(this);
break;
default:
break;
}
}
void WaypointList::on_clearWPListButton_clicked()
{
if (uas)
{
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
}
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *temp = waypoints.at(indexWP);
temp->setX(coordinate.x());
temp->setY(coordinate.y());
//WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
//widget->updateValues();
}
}
}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
//}
void WaypointList::clearWPWidget()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
//emit changePositionWPBySpinBox(wp->getId(), wp->getY(), wp->getX());
}
void WaypointList::setIsLoadFileWP()
{
loadFileGlobalWP = true;
}
void WaypointList::setIsReadGlobalWP(bool value)
{
// FIXME James Check this
Q_UNUSED(value);
// readGlobalWP = value;
}
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK 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.
PIXHAWK 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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Waypoint list widget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include "WaypointList.h"
#include "ui_WaypointList.h"
#include <UASInterface.h>
#include <UASManager.h>
#include <QDebug>
#include <QFileDialog>
#include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent),
uas(NULL),
mavX(0.0),
mavY(0.0),
mavZ(0.0),
mavYaw(0.0),
m_ui(new Ui::WaypointList)
{
m_ui->setupUi(this);
listLayout = new QVBoxLayout(m_ui->listWidget);
listLayout->setSpacing(6);
listLayout->setMargin(0);
listLayout->setAlignment(Qt::AlignTop);
m_ui->listWidget->setLayout(listLayout);
// ADD WAYPOINT
// Connect add action, set right button icon and connect action to this class
connect(m_ui->addButton, SIGNAL(clicked()), m_ui->actionAddWaypoint, SIGNAL(triggered()));
connect(m_ui->actionAddWaypoint, SIGNAL(triggered()), this, SLOT(add()));
// ADD WAYPOINT AT CURRENT POSITION
connect(m_ui->positionAddButton, SIGNAL(clicked()), this, SLOT(addCurrentPositonWaypoint()));
// SEND WAYPOINTS
connect(m_ui->transmitButton, SIGNAL(clicked()), this, SLOT(transmit()));
// REQUEST WAYPOINTS
connect(m_ui->readButton, SIGNAL(clicked()), this, SLOT(read()));
// SAVE/LOAD WAYPOINTS
connect(m_ui->saveButton, SIGNAL(clicked()), this, SLOT(saveWaypoints()));
connect(m_ui->loadButton, SIGNAL(clicked()), this, SLOT(loadWaypoints()));
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
setUAS(uas);
// STATUS LABEL
updateStatusLabel("");
this->setVisible(false);
loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
}
WaypointList::~WaypointList()
{
delete m_ui;
}
void WaypointList::updatePosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
mavX = x;
mavY = y;
mavZ = z;
}
void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
Q_UNUSED(roll);
Q_UNUSED(pitch);
mavYaw = yaw;
}
void WaypointList::setUAS(UASInterface* uas)
{
if (this->uas == NULL && uas != NULL)
{
this->uas = uas;
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int,Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
void WaypointList::saveWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
uas->getWaypointManager()->saveWaypoints(fileName);
}
}
void WaypointList::loadWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager()->loadWaypoints(fileName);
}
}
void WaypointList::transmit()
{
if (uas)
{
uas->getWaypointManager()->writeWaypoints();
}
}
void WaypointList::read()
{
if (uas)
{
uas->getWaypointManager()->readWaypoints();
}
}
void WaypointList::add()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
Waypoint *wp;
if (waypoints.size() > 0)
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(),
last->getHoldTime(), last->getFrame(), last->getAction());
uas->getWaypointManager()->addWaypoint(wp);
}
else
{
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLongitude(), uas->getLatitude(), uas->getAltitude(), 0.0, true, true, 0.15, 0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE);
uas->getWaypointManager()->addWaypoint(wp);
}
// if (wp->getFrame() == MAV_FRAME_GLOBAL)
// {
// emit createWaypointAtMap(QPointF(wp->getX(), wp->getY()));
// }
}
}
void WaypointList::addCurrentPositonWaypoint()
{
/* TODO: implement with new waypoint structure
if (uas)
{
// For Global Waypoints
//if(isGlobalWP)
//{
//isLocalWP = false;
//}
//else
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager()->addWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager()->addWaypoint(wp);
}
//isLocalWP = true;
}
}
*/
}
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
{
if (uas)
{
uas->getWaypointManager()->setCurrentWaypoint(seq);
}
}
void WaypointList::currentWaypointChanged(quint16 seq)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
widget->setCurrent(true);
}
else
{
widget->setCurrent(false);
}
}
}
}
}
void WaypointList::updateWaypoint(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues();
}
void WaypointList::waypointListChanged()
{
if (uas)
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (!wpViews.empty())
{
QMapIterator<Waypoint*,WaypointView*> viewIt(wpViews);
viewIt.toFront();
while(viewIt.hasNext())
{
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == cur)
{
break;
}
}
if (i == waypoints.size())
{
WaypointView* widget = wpViews.find(cur).value();
widget->hide();
listLayout->removeWidget(widget);
wpViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint *wp = waypoints[i];
if (!wpViews.contains(wp))
{
WaypointView* wpview = new WaypointView(wp, this);
wpViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
}
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues(); // update the values of the ui elements in the view
listLayout->addWidget(wpv);
}
this->setUpdatesEnabled(true);
}
loadFileGlobalWP = false;
}
void WaypointList::moveUp(Waypoint* wp)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the first entry, move it
if (i < waypoints.size() && i > 0)
{
uas->getWaypointManager()->moveWaypoint(i, i-1);
}
}
//emitir señal de cambio orden en la lista,
//la debe capturar el mapwidget para volver a dibujar la ruta
}
void WaypointList::moveDown(Waypoint* wp)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++)
{
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the last entry, move it
if (i < waypoints.size()-1)
{
uas->getWaypointManager()->moveWaypoint(i, i+1);
}
}
}
void WaypointList::removeWaypoint(Waypoint* wp)
{
if (uas)
{
uas->getWaypointManager()->removeWaypoint(wp->getId());
}
}
void WaypointList::changeEvent(QEvent *e)
{
switch (e->type()) {
case QEvent::LanguageChange:
m_ui->retranslateUi(this);
break;
default:
break;
}
}
void WaypointList::on_clearWPListButton_clicked()
{
if (uas)
{
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
}
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *temp = waypoints.at(indexWP);
temp->setX(coordinate.x());
temp->setY(coordinate.y());
//WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
//widget->updateValues();
}
}
}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
//}
void WaypointList::clearWPWidget()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager()->getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
//emit changePositionWPBySpinBox(wp->getId(), wp->getY(), wp->getX());
}
void WaypointList::setIsLoadFileWP()
{
loadFileGlobalWP = true;
}
void WaypointList::setIsReadGlobalWP(bool value)
{
// FIXME James Check this
Q_UNUSED(value);
// readGlobalWP = value;
}

278
src/ui/designer/QGCActionButton.cc

@ -1,139 +1,139 @@ @@ -1,139 +1,139 @@
#include "QGCActionButton.h"
#include "ui_QGCActionButton.h"
#include "MAVLinkProtocol.h"
#include "UASManager.h"
const char* kActionLabels[MAV_ACTION_NB] =
{"HOLD",
"START MOTORS",
"LAUNCH",
"RETURN",
"EMERGENCY LAND",
"EMERGENCY KILL",
"CONFIRM KILL",
"CONTINUE",
"STOP MOTORS",
"HALT",
"SHUTDOWN",
"REBOOT",
"SET MANUAL",
"SET AUTO",
"READ STORAGE",
"WRITE STORAGE",
"CALIBRATE RC",
"CALIBRATE GYRO",
"CALIBRATE MAG",
"CALIBRATE ACC",
"CALIBRATE PRESSURE",
"START REC",
"PAUSE REC",
"STOP REC",
"TAKEOFF",
"NAVIGATE",
"LAND",
"LOITER",
"SET ORIGIN",
"RELAY ON",
//"RELAY OFF",
//"GET IMAGE",
//"START VIDEO",
//"STOP VIDEO",
"RESET MAP",
"RESET PLAN"};
QGCActionButton::QGCActionButton(QWidget *parent) :
QGCToolWidgetItem("Button", parent),
ui(new Ui::QGCActionButton),
uas(NULL)
{
ui->setupUi(this);
connect(ui->actionButton, SIGNAL(clicked()), this, SLOT(sendAction()));
connect(ui->editFinishButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
connect(ui->editButtonName, SIGNAL(textChanged(QString)), this, SLOT(setActionButtonName(QString)));
connect(ui->editActionComboBox, SIGNAL(currentIndexChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
// Hide all edit items
ui->editActionComboBox->hide();
ui->editActionsRefreshButton->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
// add action labels to combobox
for (int i = 0; i < MAV_ACTION_NB; i++)
{
ui->editActionComboBox->addItem(kActionLabels[i]);
}
}
QGCActionButton::~QGCActionButton()
{
delete ui;
}
void QGCActionButton::sendAction()
{
if (QGCToolWidgetItem::uas)
{
MAV_ACTION action = static_cast<MAV_ACTION>(
ui->editActionComboBox->currentIndex());
QGCToolWidgetItem::uas->setAction(action);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}
void QGCActionButton::setActionButtonName(QString text)
{
ui->actionButton->setText(text);
}
void QGCActionButton::startEditMode()
{
ui->editActionComboBox->show();
ui->editActionsRefreshButton->show();
ui->editFinishButton->show();
ui->editNameLabel->show();
ui->editButtonName->show();
isInEditMode = true;
}
void QGCActionButton::endEditMode()
{
ui->editActionComboBox->hide();
ui->editActionsRefreshButton->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
// Write to settings
emit editingFinished();
isInEditMode = false;
}
void QGCActionButton::writeSettings(QSettings& settings)
{
settings.setValue("TYPE", "BUTTON");
settings.setValue("QGC_ACTION_BUTTON_DESCRIPTION", ui->nameLabel->text());
settings.setValue("QGC_ACTION_BUTTON_BUTTONTEXT", ui->actionButton->text());
settings.setValue("QGC_ACTION_BUTTON_ACTIONID", ui->editActionComboBox->currentIndex());
settings.sync();
}
void QGCActionButton::readSettings(const QSettings& settings)
{
ui->editNameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->editButtonName->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editActionComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
ui->nameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->actionButton->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editActionComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
qDebug() << "DONE READING SETTINGS";
}
#include "QGCActionButton.h"
#include "ui_QGCActionButton.h"
#include "MAVLinkProtocol.h"
#include "UASManager.h"
const char* kActionLabels[MAV_ACTION_NB] =
{"HOLD",
"START MOTORS",
"LAUNCH",
"RETURN",
"EMERGENCY LAND",
"EMERGENCY KILL",
"CONFIRM KILL",
"CONTINUE",
"STOP MOTORS",
"HALT",
"SHUTDOWN",
"REBOOT",
"SET MANUAL",
"SET AUTO",
"READ STORAGE",
"WRITE STORAGE",
"CALIBRATE RC",
"CALIBRATE GYRO",
"CALIBRATE MAG",
"CALIBRATE ACC",
"CALIBRATE PRESSURE",
"START REC",
"PAUSE REC",
"STOP REC",
"TAKEOFF",
"NAVIGATE",
"LAND",
"LOITER",
"SET ORIGIN",
"RELAY ON",
//"RELAY OFF",
//"GET IMAGE",
//"START VIDEO",
//"STOP VIDEO",
"RESET MAP",
"RESET PLAN"};
QGCActionButton::QGCActionButton(QWidget *parent) :
QGCToolWidgetItem("Button", parent),
ui(new Ui::QGCActionButton),
uas(NULL)
{
ui->setupUi(this);
connect(ui->actionButton, SIGNAL(clicked()), this, SLOT(sendAction()));
connect(ui->editFinishButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
connect(ui->editButtonName, SIGNAL(textChanged(QString)), this, SLOT(setActionButtonName(QString)));
connect(ui->editActionComboBox, SIGNAL(currentIndexChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
// Hide all edit items
ui->editActionComboBox->hide();
ui->editActionsRefreshButton->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
// add action labels to combobox
for (int i = 0; i < MAV_ACTION_NB; i++)
{
ui->editActionComboBox->addItem(kActionLabels[i]);
}
}
QGCActionButton::~QGCActionButton()
{
delete ui;
}
void QGCActionButton::sendAction()
{
if (QGCToolWidgetItem::uas)
{
MAV_ACTION action = static_cast<MAV_ACTION>(
ui->editActionComboBox->currentIndex());
QGCToolWidgetItem::uas->setAction(action);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}
void QGCActionButton::setActionButtonName(QString text)
{
ui->actionButton->setText(text);
}
void QGCActionButton::startEditMode()
{
ui->editActionComboBox->show();
ui->editActionsRefreshButton->show();
ui->editFinishButton->show();
ui->editNameLabel->show();
ui->editButtonName->show();
isInEditMode = true;
}
void QGCActionButton::endEditMode()
{
ui->editActionComboBox->hide();
ui->editActionsRefreshButton->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
// Write to settings
emit editingFinished();
isInEditMode = false;
}
void QGCActionButton::writeSettings(QSettings& settings)
{
settings.setValue("TYPE", "BUTTON");
settings.setValue("QGC_ACTION_BUTTON_DESCRIPTION", ui->nameLabel->text());
settings.setValue("QGC_ACTION_BUTTON_BUTTONTEXT", ui->actionButton->text());
settings.setValue("QGC_ACTION_BUTTON_ACTIONID", ui->editActionComboBox->currentIndex());
settings.sync();
}
void QGCActionButton::readSettings(const QSettings& settings)
{
ui->editNameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->editButtonName->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editActionComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
ui->nameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->actionButton->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editActionComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
qDebug() << "DONE READING SETTINGS";
}

1252
src/ui/uas/UASView.cc

File diff suppressed because it is too large Load Diff
Loading…
Cancel
Save