Commit cb002ae9 authored by pixhawk's avatar pixhawk

Bugfixes to waypoint interface, added UAS icons

parent 0d1969c0
/*=====================================================================
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
......@@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project
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/>.
======================================================================*/
/**
......@@ -34,23 +33,24 @@ This file is part of the QGROUNDCONTROL project
#include <QStringList>
Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _autocontinue, bool _current, float _orbit, int _holdTime, MAV_FRAME _frame, MAV_ACTION _action)
: id(_id),
x(_x),
y(_y),
z(_z),
yaw(_yaw),
frame(_frame),
action(_action),
autocontinue(_autocontinue),
current(_current),
orbit(_orbit),
holdTime(_holdTime)
: id(_id),
x(_x),
y(_y),
z(_z),
yaw(_yaw),
frame(_frame),
action(_action),
autocontinue(_autocontinue),
current(_current),
orbit(_orbit),
holdTime(_holdTime),
name(QString("WP%1").arg(id, 2, 10, QChar('0')))
{
}
Waypoint::~Waypoint()
{
}
void Waypoint::save(QTextStream &saveStream)
......@@ -90,79 +90,141 @@ bool Waypoint::load(QTextStream &loadStream)
void Waypoint::setId(quint16 id)
{
this->id = id;
this->name = QString("WP%1").arg(id, 2, 10, QChar('0'));
emit changed(this);
}
void Waypoint::setX(float x)
{
this->x = x;
if (this->x != x)
{
this->x = x;
emit changed(this);
}
}
void Waypoint::setY(float y)
{
this->y = y;
if (this->y != y)
{
this->y = y;
emit changed(this);
}
}
void Waypoint::setZ(float z)
{
this->z = z;
if (this->z != z)
{
this->z = z;
emit changed(this);
}
}
void Waypoint::setYaw(float yaw)
{
this->yaw = yaw;
if (this->yaw != yaw)
{
this->yaw = yaw;
emit changed(this);
}
}
void Waypoint::setAction(MAV_ACTION action)
{
this->action = action;
if (this->action != action)
{
this->action = action;
emit changed(this);
}
}
void Waypoint::setFrame(MAV_FRAME frame)
{
this->frame = frame;
if (this->frame != frame)
{
this->frame = frame;
emit changed(this);
}
}
void Waypoint::setAutocontinue(bool autoContinue)
{
this->autocontinue = autoContinue;
if (this->autocontinue != autocontinue)
{
this->autocontinue = autoContinue;
emit changed(this);
}
}
void Waypoint::setCurrent(bool current)
{
this->current = current;
if (this->current != current)
{
this->current = current;
emit changed(this);
}
}
void Waypoint::setOrbit(float orbit)
{
this->orbit = orbit;
if (this->orbit != orbit)
{
this->orbit = orbit;
emit changed(this);
}
}
void Waypoint::setHoldTime(int holdTime)
{
this->holdTime = holdTime;
if (this->holdTime != holdTime)
{
this->holdTime = holdTime;
emit changed(this);
}
}
void Waypoint::setX(double x)
{
this->x = x;
if (this->x != static_cast<float>(x))
{
this->x = x;
emit changed(this);
}
}
void Waypoint::setY(double y)
{
this->y = y;
if (this->y != static_cast<float>(y))
{
this->y = y;
emit changed(this);
}
}
void Waypoint::setZ(double z)
{
this->z = z;
if (this->z != static_cast<float>(z))
{
this->z = z;
emit changed(this);
}
}
void Waypoint::setYaw(double yaw)
{
this->yaw = yaw;
if (this->yaw != static_cast<float>(yaw))
{
this->yaw = yaw;
emit changed(this);
}
}
void Waypoint::setOrbit(double orbit)
{
this->orbit = orbit;
if (this->orbit != static_cast<float>(orbit))
{
this->orbit = orbit;
emit changed(this);
}
}
......@@ -59,6 +59,7 @@ public:
float getHoldTime() const { return holdTime; }
MAV_FRAME getFrame() const { return frame; }
MAV_ACTION getAction() const { return action; }
const QString& getName() const { return name; }
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
......@@ -76,6 +77,7 @@ protected:
bool current;
float orbit;
int holdTime;
QString name;
public slots:
void setId(quint16 id);
......@@ -97,6 +99,10 @@ public slots:
void setZ(double z);
void setYaw(double yaw);
void setOrbit(double orbit);
signals:
/** @brief Announces a change to the waypoint data */
void changed(Waypoint* wp);
};
#endif // WAYPOINT_H
......@@ -17,7 +17,7 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha)"
#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha RC6)"
namespace QGC
......
......@@ -1038,7 +1038,7 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
break;
case MAV_STATE_EMERGENCY:
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Please land");
stateDescription = tr("EMERGENCY: Land!");
break;
case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN");
......
......@@ -267,9 +267,16 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
void UASWaypointManager::notifyOfChange(Waypoint* wp)
{
Q_UNUSED(wp);
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
// If only one waypoint was changed, emit only WP signal
if (wp != NULL)
{
emit waypointChanged(uas.getUASID(), wp);
}
else
{
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
}
}
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
......@@ -318,11 +325,10 @@ void UASWaypointManager::addWaypoint(Waypoint *wp)
{
wp->setId(waypoints.size());
waypoints.insert(waypoints.size(), wp);
connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChange(Waypoint*)));
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
qDebug() << "ADDED WAYPOINT WITH ID:" << wp->getId();
}
}
......
......@@ -86,16 +86,6 @@ public:
/** @name Waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the waypoint list.
int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint
void localAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int localRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void localMoveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void localSaveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void localLoadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
int getIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list
/*@}*/
......@@ -122,7 +112,15 @@ private:
public slots:
void timeout(); ///< Called by the timer if a response times out. Handles send retries.
/** @name Waypoint list operations */
/*@{*/
void addWaypoint(Waypoint *wp); ///< adds a new waypoint to the end of the list and changes its sequence number accordingly
int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint
/*@}*/
signals:
void waypointListChanged(void); ///< emits signal that the waypoint list has been changed
......
......@@ -38,7 +38,7 @@
#include "SlugsMAV.h"
#include "LogCompressor.h"
#include "LogCompressor.h"s
MainWindow* MainWindow::instance()
{
......@@ -72,13 +72,6 @@ MainWindow::MainWindow(QWidget *parent):
{
// Set this view as default view
settings.setValue("CURRENT_VIEW", currentView);
// Enable default tools
// ENABLE UAS LIST
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST,currentView), true);
// ENABLE COMMUNICATION CONSOLE
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_DEBUG_CONSOLE,currentView), true);
}
else
{
......@@ -98,32 +91,9 @@ MainWindow::MainWindow(QWidget *parent):
// Setup user interface
ui.setupUi(this);
ui.actionNewCustomWidget->setEnabled(false);
setVisible(false);
// Bind together the perspective actions
QActionGroup* perspectives = new QActionGroup(ui.menuPerspectives);
perspectives->addAction(ui.actionEngineersView);
perspectives->addAction(ui.actionMavlinkView);
perspectives->addAction(ui.actionPilotsView);
perspectives->addAction(ui.actionOperatorsView);
perspectives->addAction(ui.actionUnconnectedView);
perspectives->setExclusive(true);
// Mark the right one as selected
if (currentView == VIEW_ENGINEER) ui.actionEngineersView->setChecked(true);
if (currentView == VIEW_MAVLINK) ui.actionMavlinkView->setChecked(true);
if (currentView == VIEW_PILOT) ui.actionPilotsView->setChecked(true);
if (currentView == VIEW_OPERATOR) ui.actionOperatorsView->setChecked(true);
if (currentView == VIEW_UNCONNECTED) ui.actionUnconnectedView->setChecked(true);
// The pilot, engineer and operator view are not available on startup
// since they only make sense with a system connected.
ui.actionPilotsView->setEnabled(false);
ui.actionOperatorsView->setEnabled(false);
ui.actionEngineersView->setEnabled(false);
buildCommonWidgets();
connectCommonWidgets();
......@@ -204,6 +174,11 @@ void MainWindow::setDefaultSettingsForAp()
if (!settings.contains(centralKey))
{
settings.setValue(centralKey,true);
// ENABLE UAS LIST
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST, VIEW_UNCONNECTED), true);
// ENABLE COMMUNICATION CONSOLE
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_DEBUG_CONSOLE, VIEW_UNCONNECTED), true);
}
// OPERATOR VIEW DEFAULT
......@@ -223,6 +198,8 @@ void MainWindow::setDefaultSettingsForAp()
if (!settings.contains(centralKey))
{
settings.setValue(centralKey,true);
// Enable Parameter widget
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_PARAMETERS,VIEW_ENGINEER), true);
}
// MAVLINK VIEW DEFAULT
......@@ -237,6 +214,8 @@ void MainWindow::setDefaultSettingsForAp()
if (!settings.contains(centralKey))
{
settings.setValue(centralKey,true);
// Enable Flight display
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_HDD_1,VIEW_PILOT), true);
}
}
......@@ -895,9 +874,11 @@ QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES t
// Key is built as follows: autopilot_type/section_menu/view/tool/section
int apType;
apType = (UASManager::instance() && UASManager::instance()->silentGetActiveUAS())?
UASManager::instance()->getActiveUAS()->getAutopilotType():
-1;
// apType = (UASManager::instance() && UASManager::instance()->silentGetActiveUAS())?
// UASManager::instance()->getActiveUAS()->getAutopilotType():
// -1;
apType = 1;
return (QString::number(apType) + "_" +
QString::number(SECTION_MENU) + "_" +
......@@ -1266,6 +1247,36 @@ void MainWindow::showInfoMessage(const QString& title, const QString& message)
**/
void MainWindow::connectCommonActions()
{
ui.actionNewCustomWidget->setEnabled(false);
// Bind together the perspective actions
QActionGroup* perspectives = new QActionGroup(ui.menuPerspectives);
perspectives->addAction(ui.actionEngineersView);
perspectives->addAction(ui.actionMavlinkView);
perspectives->addAction(ui.actionPilotsView);
perspectives->addAction(ui.actionOperatorsView);
perspectives->addAction(ui.actionUnconnectedView);
perspectives->setExclusive(true);
// Mark the right one as selected
if (currentView == VIEW_ENGINEER) ui.actionEngineersView->setChecked(true);
if (currentView == VIEW_MAVLINK) ui.actionMavlinkView->setChecked(true);
if (currentView == VIEW_PILOT) ui.actionPilotsView->setChecked(true);
if (currentView == VIEW_OPERATOR) ui.actionOperatorsView->setChecked(true);
if (currentView == VIEW_UNCONNECTED) ui.actionUnconnectedView->setChecked(true);
// The pilot, engineer and operator view are not available on startup
// since they only make sense with a system connected.
ui.actionPilotsView->setEnabled(false);
ui.actionOperatorsView->setEnabled(false);
ui.actionEngineersView->setEnabled(false);
// The UAS actions are not enabled without connection to system
ui.actionLiftoff->setEnabled(false);
ui.actionLand->setEnabled(false);
ui.actionEmergency_Kill->setEnabled(false);
ui.actionEmergency_Land->setEnabled(false);
ui.actionShutdownMAV->setEnabled(false);
// Connect actions from ui
connect(ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(addLink()));
......@@ -1278,7 +1289,7 @@ void MainWindow::connectCommonActions()
connect(ui.actionLand, SIGNAL(triggered()), UASManager::instance(), SLOT(returnActiveUAS()));
connect(ui.actionEmergency_Land, SIGNAL(triggered()), UASManager::instance(), SLOT(stopActiveUAS()));
connect(ui.actionEmergency_Kill, SIGNAL(triggered()), UASManager::instance(), SLOT(killActiveUAS()));
connect(ui.actionShutdownMAV, SIGNAL(triggered()), UASManager::instance(), SLOT(shutdownActiveUAS()));
connect(ui.actionConfiguration, SIGNAL(triggered()), UASManager::instance(), SLOT(configureActiveUAS()));
// Views actions
......@@ -1439,6 +1450,12 @@ void MainWindow::UASCreated(UASInterface* uas)
ui.actionPilotsView->setEnabled(true);
ui.actionOperatorsView->setEnabled(true);
ui.actionEngineersView->setEnabled(true);
// The UAS actions are not enabled without connection to system
ui.actionLiftoff->setEnabled(true);
ui.actionLand->setEnabled(true);
ui.actionEmergency_Kill->setEnabled(true);
ui.actionEmergency_Land->setEnabled(true);
ui.actionShutdownMAV->setEnabled(true);
QIcon icon;
// Set matching icon
......@@ -1644,6 +1661,7 @@ void MainWindow::clearView()
{
// Remove dock widget from main window
removeDockWidget(dockWidget);
dockWidget->hide();
//dockWidget->setVisible(false);
}
}
......
......@@ -77,7 +77,7 @@
</widget>
<widget class="QMenu" name="menuConnected_Systems">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="title">
<string>Select System</string>
......@@ -85,7 +85,7 @@
</widget>
<widget class="QMenu" name="menuUnmanned_System">
<property name="enabled">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="title">
<string>Unmanned System</string>
......@@ -93,6 +93,7 @@
<property name="separatorsCollapsible">
<bool>false</bool>
</property>
<addaction name="actionShutdownMAV"/>
<addaction name="actionLiftoff"/>
<addaction name="actionLand"/>
<addaction name="actionEmergency_Land"/>
......@@ -413,6 +414,21 @@
<string>Meta+U</string>
</property>
</action>
<action name="actionShutdownMAV">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/system-log-out.svg</normaloff>:/images/actions/system-log-out.svg</iconset>
</property>
<property name="text">
<string>Shutdown MAV</string>
</property>
<property name="toolTip">
<string>Shutdown the onboard computer - works not during flight</string>
</property>
<property name="statusTip">
<string>Shutdown the onboard computer - works not during flight</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -632,6 +632,7 @@ MapWidget::~MapWidget()
void MapWidget::addUAS(UASInterface* uas)
{
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(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(waypointListChanged()), this, SLOT(redoWaypoints()));
}
......@@ -700,14 +701,10 @@ void MapWidget::activeUASSet(UASInterface* uas)
// Disconnect old MAV
if (mav)
{
// clear path create on the map
// Disconnect the waypoint manager / data storage from the UI
disconnect(mav->getWaypointManager(), SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int)));
// add Waypoint widget in the WaypointList widget when mouse clicked
disconnect(mav->getWaypointManager(), SIGNAL(waypointUpdated(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
disconnect(this, SIGNAL(waypointCreated(Waypoint*)), mav->getWaypointManager(), SLOT(addWaypoint(Waypoint*)));
// it notifies that a waypoint global goes to do create and a map graphic too
//connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
}
if (uas)
......@@ -721,16 +718,32 @@ void MapWidget::activeUASSet(UASInterface* uas)
// FIXME Remove after refactoring
waypointPath->setPen(pen);
// Delete all waypoints and start fresh
// Delete all waypoints and add waypoint from new system
redoWaypoints();
// clear path create on the map
// Connect the waypoint manager / data storage to the UI
connect(mav->getWaypointManager(), SIGNAL(waypointListChanged(int)), this, SLOT(updateWaypointList(int)));
// add Waypoint widget in the WaypointList widget when mouse clicked
connect(mav->getWaypointManager(), SIGNAL(waypointUpdated(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), mav->getWaypointManager(), SLOT(addWaypoint(Waypoint*)));
}
}
void MapWidget::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
{
Q_UNUSED(roll);
Q_UNUSED(pitch);
Q_UNUSED(usec);
if (uas)
{
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID(), NULL));
if (icon)
{
icon->setYaw(yaw);
}
}
}
/**
* Updates the global position of one MAV and append the last movement to the trail
*
......@@ -766,24 +779,24 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
//QPen* pointpen = new QPen(uasColor);
qDebug() << "2D MAP: ADDING" << uas->getUASName() << __FILE__ << __LINE__;
//p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, mavPens.value(uas->getUASID()));
p = new Waypoint2DIcon(lat, lon, 20, QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
p = new MAV2DIcon(lat, lon, 50, uas->getSystemType(), uas->getColor(), QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
uasIcons.insert(uas->getUASID(), p);
mc->layer("Waypoints")->addGeometry(p);
// Line
// A QPen also can use transparency
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// QList<qmapcontrol::Point*> points;
// points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// QPen* linepen = new QPen(uasColor.darker());
// linepen->setWidth(2);
// Create tracking line string
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
uasTrails.insert(uas->getUASID(), ls);
// // Create tracking line string
// qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
// uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
mc->layer("Waypoints")->addGeometry(ls);
// // Add the LineString to the layer
// mc->layer("Waypoints")->addGeometry(ls);
}
else
{
......@@ -795,7 +808,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
//p->setYaw(uas->getYaw());
// }
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
}
mc->updateRequest(p->boundingBox().toRect());
......
......@@ -68,6 +68,8 @@ public:
public slots:
void addUAS(UASInterface* uas);
void activeUASSet(UASInterface* uas);
/** @brief Update the attitude */
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
void updateCameraPosition(double distance, double bearing, QString dir);
......
......@@ -146,10 +146,20 @@ QPushButton:pressed#killButton {
}
QProgressBar {
QProgressBar:horizontal {
border: 1px solid #4A4A4F;
border-radius: 4px;
text-align: center;
padding: 2px;
color: #DDDDDF;
background-color: #111118;
}
QProgressBar:vertical {
border: 1px solid #4A4A4F;
border-radius: 4px;
text-align: center;
font-size: 7px;
padding: 2px;
color: #DDDDDF;
background-color: #111118;
......@@ -159,12 +169,16 @@ QProgressBar:horizontal {
height: 10px;
}
QProgressBar QLabel {
font-size: 8px;
QProgressBar:horizontal QLabel {
font-size: 9px;
}
QProgressBar:vertical QLabel {
font-size: 7px;
}
QProgressBar:vertical {
width: 12px;
width: 14px;
}
QProgressBar::chunk {
......@@ -231,7 +245,7 @@ QMenu::separator {
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout">
<layout class="QGridLayout" name="gridLayout" columnstretch="10,10,1,10,10,10,100,100">
<property name="horizontalSpacing">
<number>4</number>
</property>
......@@ -281,9 +295,12 @@ QMenu::separator {
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>6</width>
<width>4</width>
<height>88</height>
</size>
</property>
......@@ -327,7 +344,7 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string>Waiting for first update..</string>
<string/>
</property>
</widget>
</item>
......@@ -466,7 +483,7 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string>UNINIT</string>
<string/>
</property>
</widget>
</item>
......@@ -481,14 +498,14 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string>WPX</string>
<string>---</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
</widget>
</item>
<item row="2" column="6">
<item row="2" column="6" colspan="2">
<widget class="QLabel" name="positionLabel">
<property name="minimumSize">
<size>
......@@ -515,33 +532,6 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="2" column="7">
<widget class="QLabel" name="gpsLabel">
<property name="minimumSize">
<size>
<width>0</width>
<height>12</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>12</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>00 00 00 N 00 00 00 E</string>
</property>
</widget>
</item>
<item row="5" column="6" colspan="2">
<widget class="QLabel" name="statusTextLabel">
<property name="maximumSize">
......@@ -556,7 +546,7 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string>Unknown status</string>
<string/>
</property>
</widget>
</item>
......
......@@ -129,6 +129,7 @@ void WaypointList::setUAS(UASInterface* uas)
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)));
......@@ -214,10 +215,10 @@ void WaypointList::add()
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()));
}
// if (wp->getFrame() == MAV_FRAME_GLOBAL)
// {
// emit createWaypointAtMap(QPointF(wp->getX(), wp->getY()));
// }
}
}
}
......@@ -293,6 +294,13 @@ void WaypointList::currentWaypointChanged(quint16 seq)
}
}
void WaypointList::updateWaypoint(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointView *wpv = wpViews.value(wp);
wpv->updateValues();
}
void WaypointList::waypointListChanged()
{
if (uas)
......
......@@ -65,7 +65,7 @@ public slots:
/** @brief Save the local waypoint list to a file */
void saveWaypoints();
/** @brief Load a waypoint list from a file */
void loadWaypoints();
void loadWaypoints();
/** @brief Transmit the local waypoint list to the UAS */
void transmit();
/** @brief Read the remote waypoint list */
......@@ -87,6 +87,8 @@ public slots:
void changeCurrentWaypoint(quint16 seq);
/** @brief The waypoint planner changed the current waypoint */
void currentWaypointChanged(quint16 seq);
/** @brief The waypoint manager informs that one waypoint was changed */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief The waypoint manager informs that the waypoint list was changed */
void waypointListChanged(void);
......@@ -111,10 +113,6 @@ public slots:
signals:
void clearPathclicked();
void createWaypointAtMap(const QPointF coordinate);
// void ChangeWaypointGlobalPosition(int index, QPointF coord);
void changePositionWPBySpinBox(int indexWP, float lat, float lon);
protected:
virtual void changeEvent(QEvent *e);
......
#include "MAV2DIcon.h"
#include <QPainter>
MAV2DIcon::MAV2DIcon(qreal x, qreal y, int radius, QString name, Alignment alignment, QPen* pen)
#include <qmath.h>
MAV2DIcon::MAV2DIcon(qreal x, qreal y, int radius, int type, const QColor& color, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment),
yaw(0.0f)
yaw(0.0f),
radius(radius),
type(type),
iconColor(color)
{
size = QSize(radius, radius);
drawIcon(pen);
}
MAV2DIcon::MAV2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment)
: Point(x, y, name, alignment),
radius(20),
type(0),
iconColor(Qt::yellow)
{
int radius = 10;
size = QSize(radius, radius);
if (pen)
{
drawIcon(pen);
}
drawIcon(pen);
}
MAV2DIcon::~MAV2DIcon()
......@@ -27,69 +31,110 @@ MAV2DIcon::~MAV2DIcon()
void MAV2DIcon::setPen(QPen* pen)
{
if (pen)
{
mypen = pen;
drawIcon(pen);
}
mypen = pen;
drawIcon(pen);
}
/**
* Yaw changes of less than ±15 degrees are ignored.
*
* @param yaw in radians, 0 = north, positive = clockwise
*/
void MAV2DIcon::setYaw(float yaw)
{
this->yaw = yaw;
drawIcon(mypen);
float diff = fabs(yaw - this->yaw);
while (diff > M_PI)
{
diff -= M_PI;
}
if (diff > 0.25)
{
this->yaw = yaw;
drawIcon(mypen);
}
}
void MAV2DIcon::drawIcon(QPen* pen)
{
switch (type)
{
case MAV_ICON_GENERIC:
case MAV_ICON_AIRPLANE:
case MAV_ICON_QUADROTOR:
case MAV_ICON_ROTARY_WING:
default:
{
mypixmap = new QPixmap(radius+1, radius+1);
mypixmap->fill(Qt::transparent);
QPainter painter(mypixmap);
painter.setRenderHint(QPainter::TextAntialiasing);
painter.setRenderHint(QPainter::Antialiasing);
painter.setRenderHint(QPainter::HighQualityAntialiasing);
mypixmap = new QPixmap(radius+1, radius+1);
mypixmap->fill(Qt::transparent);
QPainter painter(mypixmap);
// Rotate by yaw
painter.translate(radius/2, radius/2);
painter.rotate(((yaw/(float)M_PI)+1.0f)*360.0f);
// DRAW WAYPOINT
QPointF p(radius/2, radius/2);
// DRAW AIRPLANE
float waypointSize = radius;
QPolygonF poly(4);
// Top point
poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f));
// Right point
poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y()));
// Bottom point
poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f));
poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));
qDebug() << "ICON SIZE:" << radius;
// // Select color based on if this is the current waypoint
// if (list.at(i)->getCurrent())
// {
// color = QGC::colorCyan;//uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.8f));
// }
// else
// {
// color = uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.4f));
// }
float iconSize = radius*0.9f;
QPolygonF poly(24);
poly.replace(0, QPointF(0.000000f*iconSize, -0.312500f*iconSize));
poly.replace(1, QPointF(0.025000f*iconSize, -0.287500f*iconSize));
poly.replace(2, QPointF(0.037500f*iconSize, -0.237500f*iconSize));
poly.replace(3, QPointF(0.031250f*iconSize, -0.187500f*iconSize));
poly.replace(4, QPointF(0.025000f*iconSize, -0.043750f*iconSize));
poly.replace(5, QPointF(0.500000f*iconSize, -0.025000f*iconSize));
poly.replace(6, QPointF(0.500000f*iconSize, 0.025000f*iconSize));
poly.replace(7, QPointF(0.025000f*iconSize, 0.043750f*iconSize));
poly.replace(8, QPointF(0.025000f*iconSize, 0.162500f*iconSize));
poly.replace(9, QPointF(0.137500f*iconSize, 0.181250f*iconSize));
poly.replace(10, QPointF(0.137500f*iconSize, 0.218750f*iconSize));
poly.replace(11, QPointF(0.025000f*iconSize, 0.206250f*iconSize));
poly.replace(12, QPointF(-0.025000f*iconSize, 0.206250f*iconSize));
poly.replace(13, QPointF(-0.137500f*iconSize, 0.218750f*iconSize));
poly.replace(14, QPointF(-0.137500f*iconSize, 0.181250f*iconSize));
poly.replace(15, QPointF(-0.025000f*iconSize, 0.162500f*iconSize));
poly.replace(16, QPointF(-0.025000f*iconSize, 0.043750f*iconSize));
poly.replace(17, QPointF(-0.500000f*iconSize, 0.025000f*iconSize));
poly.replace(18, QPointF(-0.500000f*iconSize, -0.025000f*iconSize));
poly.replace(19, QPointF(-0.025000f*iconSize, -0.043750f*iconSize));
poly.replace(20, QPointF(-0.031250f*iconSize, -0.187500f*iconSize));
poly.replace(21, QPointF(-0.037500f*iconSize, -0.237500f*iconSize));
poly.replace(22, QPointF(-0.031250f*iconSize, -0.262500f*iconSize));
poly.replace(23, QPointF(0.000000f*iconSize, -0.312500f*iconSize));
//pen.setColor(color);
if (pen)
{
pen->setWidthF(2);
painter.setPen(*pen);
}
else
{
QPen pen2(Qt::red);
pen2.setWidth(2);
painter.setPen(pen2);
}
painter.setBrush(Qt::NoBrush);
// // Select color based on if this is the current waypoint
// if (list.at(i)->getCurrent())
// {
// color = QGC::colorCyan;//uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.8f));
// }
// else
// {
// color = uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.4f));
// }
float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
painter.drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * rad);
painter.drawPolygon(poly);
//pen.setColor(color);
// if (pen)
// {
// pen->setWidthF(2);
// painter.setPen(*pen);
// }
// else
// {
// QPen pen2(Qt::red);
// pen2.setWidth(0);
// painter.setPen(pen2);
// }
painter.setBrush(QBrush(iconColor));
painter.drawPolygon(poly);
}
break;
}
}
#ifndef MAV2DICON_H
#define MAV2DICON_H
#include <QGraphicsItem>
#include "qmapcontrol.h"
class MAV2DIcon : public qmapcontrol::Point
{
public:
enum
{
MAV_ICON_GENERIC = 0,
MAV_ICON_AIRPLANE,
MAV_ICON_QUADROTOR,
MAV_ICON_ROTARY_WING
} MAV_ICON_TYPE;
/*!
*
* @param x longitude
......@@ -26,7 +34,7 @@ public:
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
MAV2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
MAV2DIcon(qreal x, qreal y, int radius = 10, int type=0, const QColor& color=QColor(Qt::red), QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
virtual ~MAV2DIcon();
//! sets the QPen which is used for drawing the circle
......@@ -38,12 +46,14 @@ public:
virtual void setPen(QPen* pen);
void setYaw(float yaw);
void drawIcon(QPen* pen);
protected:
float yaw; ///< Yaw angle of the MAV
int radius; ///< Maximum dimension of the MAV icon
float yaw; ///< Yaw angle of the MAV
int radius; ///< Radius / width of the icon
int type; ///< Type of aircraft: 0: generic, 1: airplane, 2: quadrotor, 3-n: rotary wing
QColor iconColor; ///< Color to be used for the icon
};
......
......@@ -6,6 +6,16 @@ Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, int radius, QString name, Align
yaw(0.0f),
radius(radius)
{
waypoint = NULL;
size = QSize(radius, radius);
drawIcon(pen);
}
Waypoint2DIcon::Waypoint2DIcon(Waypoint* wp, int listIndex, int radius, Alignment alignment, QPen* pen)
: Point(wp->getX(), wp->getY(), QString("%1").arg(listIndex), alignment)
{
waypoint = wp;
this->yaw = wp->getYaw();
size = QSize(radius, radius);
drawIcon(pen);
}
......@@ -13,7 +23,8 @@ Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, int radius, QString name, Align
Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment)
{
int radius = 10;
waypoint = NULL;
int radius = 20;
size = QSize(radius, radius);
drawIcon(pen);
}
......@@ -38,6 +49,18 @@ void Waypoint2DIcon::setYaw(float yaw)
drawIcon(mypen);
}
void Waypoint2DIcon::updateWaypoint()
{
if (waypoint)
{
if (waypoint->getYaw() != yaw)
{
yaw = waypoint->getYaw();
drawIcon(mypen);
}
}
}
void Waypoint2DIcon::drawIcon(QPen* pen)
{
mypixmap = new QPixmap(radius+1, radius+1);
......
......@@ -4,6 +4,8 @@
#include <QGraphicsItem>
#include "qmapcontrol.h"
#include "Waypoint.h"
class Waypoint2DIcon : public qmapcontrol::Point
{
public:
......@@ -27,7 +29,19 @@ public:
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
Waypoint2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
Waypoint2DIcon(qreal x, qreal y, int radius = 20, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
/**
*
* @param wp Waypoint
* @param listIndex Index in the waypoint list
* @param radius the radius of the circle
* @param name name of the circle point
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
Waypoint2DIcon(Waypoint* wp, int listIndex, int radius = 20, Alignment alignment = Middle, QPen* pen=0);
virtual ~Waypoint2DIcon();
//! sets the QPen which is used for drawing the circle
......@@ -42,9 +56,13 @@ public:
void drawIcon(QPen* pen);
public slots:
void updateWaypoint();
protected:
float yaw; ///< Yaw angle of the MAV
int radius; ///<
int radius; ///< Radius / diameter of the icon in pixels
Waypoint* waypoint; ///< Waypoint data container this icon represents
};
......
......@@ -51,7 +51,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
uas(uas),
load(0),
state("UNKNOWN"),
stateDesc(tr("Unknown system state")),
stateDesc(tr("Unknown state")),
mode("MAV_MODE_UNKNOWN"),
thrust(0),
isActive(false),
......@@ -129,15 +129,6 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
m_ui->killButton->hide();
m_ui->shutdownButton->hide();
if (localFrame)
{
m_ui->gpsLabel->hide();
}
else
{
m_ui->positionLabel->hide();
}
setSystemType(uas, uas->getSystemType());
}
......@@ -332,8 +323,6 @@ void UASView::updateLocalPosition(UASInterface* uas, double x, double y, double
if (!localFrame)
{
localFrame = true;
m_ui->gpsLabel->hide();
m_ui->positionLabel->show();
}
}
......@@ -471,7 +460,7 @@ void UASView::refresh()
// Position
QString position;
position = position.sprintf("%05.1f %05.1f %05.1f m", x, y, z);
position = position.sprintf("%05.1f %05.1f %06.1f m", x, y, z);
m_ui->positionLabel->setText(position);
QString globalPosition;
QString latIndicator;
......@@ -492,17 +481,17 @@ void UASView::refresh()
{
lonIndicator = "W";
}
globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %05.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
m_ui->gpsLabel->setText(globalPosition);
globalPosition = globalPosition.sprintf("%05.1f%s %05.1f%s %06.1f m", lon, lonIndicator.toStdString().c_str(), lat, latIndicator.toStdString().c_str(), alt);
m_ui->positionLabel->setText(globalPosition);
// Altitude
if (groundDistance == 0 && alt != 0)
{
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 5, 'f', 1, '0'));
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(alt, 6, 'f', 1, '0'));
}
else
{
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 5, 'f', 1, '0'));
m_ui->groundDistanceLabel->setText(QString("%1 m").arg(groundDistance, 6, 'f', 1, '0'));
}
// Speed
......
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