Commit 3458c252 authored by lm's avatar lm

Updated QGC

parent f2ec2953
......@@ -44,3 +44,4 @@ user_config.pri
*.cproject
*.sln
*.suo
*thirdParty*
......@@ -57,6 +57,11 @@ Waypoint::~Waypoint()
}
bool Waypoint::isNavigationType()
{
return (action < MAV_CMD_NAV_LAST);
}
void Waypoint::save(QTextStream &saveStream)
{
QString position("%1\t%2\t%3");
......
......@@ -71,6 +71,8 @@ public:
MAV_FRAME getFrame() const { return frame; }
MAV_CMD getAction() const { return action; }
const QString& getName() const { return name; }
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
......
......@@ -506,6 +506,22 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
return wps;
}
const QVector<Waypoint *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointList()
{
// TODO Keep this global frame list up to date
// with complete waypoint list
// instead of filtering on each request
QVector<Waypoint*> wps;
foreach (Waypoint* wp, waypoints)
{
if (wp->getFrame() == MAV_FRAME_GLOBAL && wp->isNavigationType())
{
wps.append(wp);
}
}
return wps;
}
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
return waypoints.indexOf(wp);
......@@ -531,6 +547,26 @@ int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
return -1;
}
int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp)
{
// Search through all waypoints,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints)
{
if (p->getFrame() == MAV_FRAME_GLOBAL && p->isNavigationType())
{
if (p == wp)
{
return i;
}
i++;
}
}
return -1;
}
int UASWaypointManager::getGlobalFrameCount()
{
// Search through all waypoints,
......@@ -547,6 +583,22 @@ int UASWaypointManager::getGlobalFrameCount()
return i;
}
int UASWaypointManager::getGlobalFrameAndNavTypeCount()
{
// Search through all waypoints,
// counting only those in global frame
int i = 0;
foreach (Waypoint* p, waypoints)
{
if (p->getFrame() == MAV_FRAME_GLOBAL && p->isNavigationType())
{
i++;
}
}
return i;
}
int UASWaypointManager::getLocalFrameCount()
{
// Search through all waypoints,
......
......@@ -87,11 +87,14 @@ public:
/*@{*/
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the waypoint list.
const QVector<Waypoint *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
const QVector<Waypoint *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
int getIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list
int getGlobalFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global waypoints
int getGlobalFrameAndNavTypeIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global AND navigation mode waypoints
int getLocalFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only local waypoints
int getMissionFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only mission waypoints
int getGlobalFrameCount(); ///< Get the count of global waypoints in the list
int getGlobalFrameAndNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list
int getLocalFrameCount(); ///< Get the count of local waypoints in the list
/*@}*/
......
......@@ -111,9 +111,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if(serial != 0)
{
QWidget* conf = new SerialConfigurationWindow(serial, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
//QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
//layout->addWidget(conf);
ui.linkScrollArea->setWidget(conf);
//ui.linkScrollArea->setLayout(layout);
ui.linkGroupBox->setTitle(tr("Serial Link"));
ui.linkType->setCurrentIndex(0);
//ui.linkGroupBox->setTitle(link->getName());
......@@ -123,9 +124,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if (udp != 0)
{
QWidget* conf = new QGCUDPLinkConfiguration(udp, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
//QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
//layout->addWidget(conf);
//ui.linkGroupBox->setLayout(layout);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("UDP Link"));
ui.linkType->setCurrentIndex(1);
}
......@@ -162,9 +164,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if (mavlink != 0)
{
QWidget* conf = new MAVLinkSettingsWidget(mavlink, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.protocolGroupBox);
layout->addWidget(conf);
ui.protocolGroupBox->setLayout(layout);
//QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.protocolGroupBox);
//layout->addWidget(conf);
//ui.protocolGroupBox->setLayout(layout);
ui.protocolScrollArea->setWidget(conf);
ui.protocolGroupBox->setTitle(protocol->getName()+" (Global Settings)");
}
else
......
......@@ -7,16 +7,19 @@
<x>0</x>
<y>0</y>
<width>413</width>
<height>404</height>
<height>484</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_2" rowstretch="0,0,0,100,100,0">
<layout class="QGridLayout" name="gridLayout_2" rowstretch="1,1,1,100,100,1">
<property name="margin">
<number>6</number>
</property>
<property name="spacing">
<number>6</number>
</property>
<item row="0" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
......@@ -28,7 +31,7 @@
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>10</height>
<height>5</height>
</size>
</property>
</spacer>
......@@ -73,6 +76,31 @@
<property name="title">
<string>Link</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="linkScrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>393</width>
<height>154</height>
</rect>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
<item row="4" column="0" colspan="2">
......@@ -80,6 +108,31 @@
<property name="title">
<string>Protocol</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="protocolScrollArea">
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>393</width>
<height>154</height>
</rect>
</property>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
<item row="5" column="0">
......@@ -97,6 +150,9 @@
</item>
<item row="5" column="1">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
......
......@@ -492,14 +492,14 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
if (uas == this->mav->getUASID())
{
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL)
if (wp->getFrame() == MAV_FRAME_GLOBAL && wp->isNavigationType())
{
// We're good, this is a global waypoint
// Get the index of this waypoint
// note the call to getGlobalFrameIndexOf()
// note the call to getGlobalFrameAndNavTypeIndexOf()
// as we're only handling global waypoints
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameIndexOf(wp);
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1) return;
......@@ -558,7 +558,7 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeCount())
{
updateWaypointList(uas);
}
......@@ -659,7 +659,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
// Update waypoint data storage
if (mav)
{
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList();
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
if (wps.size() > index)
{
......@@ -738,7 +738,7 @@ void MapWidget::updateWaypointList(int uas)
}
// Trim internal list to number of global waypoints in the waypoint manager list
int overSize = waypointPath->points().count() - uasInstance->getWaypointManager()->getGlobalFrameCount();
int overSize = waypointPath->points().count() - uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeCount();
if (overSize > 0)
{
// Remove n waypoints at the end of the list
......
......@@ -6,14 +6,14 @@
<rect>
<x>0</x>
<y>0</y>
<width>449</width>
<height>250</height>
<width>304</width>
<height>283</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,10">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0" columnstretch="100,1">
<property name="margin">
<number>6</number>
</property>
......@@ -284,13 +284,6 @@
</item>
</layout>
</item>
<item row="4" column="0">
<widget class="QLabel" name="portlabel_5">
<property name="text">
<string>Data bits</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="dataBitsSpinBox">
<property name="sizePolicy">
......@@ -373,12 +366,19 @@
</property>
<property name="sizeHint" stdset="0">
<size>
<width>431</width>
<height>47</height>
<width>0</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="4" column="0">
<widget class="QLabel" name="portlabel_5">
<property name="text">
<string>Data bits</string>
</property>
</widget>
</item>
</layout>
<action name="actionDelete">
<property name="text">
......
......@@ -234,14 +234,14 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL)
if (wp->getFrame() == MAV_FRAME_GLOBAL && wp->isNavigationType())
{
// We're good, this is a global waypoint
// Get the index of this waypoint
// note the call to getGlobalFrameIndexOf()
// note the call to getGlobalFrameAndNavTypeIndexOf()
// as we're only handling global waypoints
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameIndexOf(wp);
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameAndNavTypeIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1)
{
......@@ -267,7 +267,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
if (uasInstance)
{
// Get all waypoints, including non-global waypoints
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameWaypointList();
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
// Trim internal list to number of global waypoints in the waypoint manager list
javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count()));
......@@ -741,7 +741,7 @@ void QGCGoogleEarthView::updateState()
// Update waypoint or symbol
if (mav)
{
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList();
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
bool ok;
int index = idText.toInt(&ok);
......
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