Commit 040e413a authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'experimental' of github.com:pixhawk/qgroundcontrol into mergeRemote

parents 9a5db5fb 64b543c4
...@@ -44,3 +44,4 @@ user_config.pri ...@@ -44,3 +44,4 @@ user_config.pri
*.cproject *.cproject
*.sln *.sln
*.suo *.suo
*thirdParty*
...@@ -77,7 +77,8 @@ enable_language(CXX) ...@@ -77,7 +77,8 @@ enable_language(CXX)
# installer # installer
include(InstallRequiredSystemLibraries) include(InstallRequiredSystemLibraries)
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${qgroundcontrol_VERSION}") set(CPACK_PACKAGE_NAME "${PROJECT_NAME}-${qgroundcontrol_VERSION}-cpack")
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${qgroundcontrol_VERSION}-cpack")
set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${qgroundcontrol_VERSION}") set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${qgroundcontrol_VERSION}")
set(CPACK_GENERATOR "DEB") set(CPACK_GENERATOR "DEB")
set(CPACK_SOURCE_GENERATOR "TGZ") set(CPACK_SOURCE_GENERATOR "TGZ")
...@@ -124,7 +125,7 @@ if (UNIX) ...@@ -124,7 +125,7 @@ if (UNIX)
endif(UNIX) endif(UNIX)
find_package(OpenGL REQUIRED) find_package(OpenGL REQUIRED)
find_package(OpenSceneGraph 2.9.9 COMPONENTS osgGA osgDB osgUtil osgViewer) find_package(OpenSceneGraph 2.9.9 COMPONENTS osgGA osgDB osgUtil osgViewer)
if ("OSG_LIBRARY" STREQUAL "${OSG_LIBRARY}") if ("OSG_LIBRARY-NOTFOUND" STREQUAL "${OSG_LIBRARY}")
set(OPENSCENEGRAPH_FOUND FALSE) set(OPENSCENEGRAPH_FOUND FALSE)
else() else()
set(OPENSCENEGRAPH_FOUND TRUE) set(OPENSCENEGRAPH_FOUND TRUE)
......
...@@ -57,6 +57,11 @@ Waypoint::~Waypoint() ...@@ -57,6 +57,11 @@ Waypoint::~Waypoint()
} }
bool Waypoint::isNavigationType()
{
return (action < MAV_CMD_NAV_LAST);
}
void Waypoint::save(QTextStream &saveStream) void Waypoint::save(QTextStream &saveStream)
{ {
QString position("%1\t%2\t%3"); QString position("%1\t%2\t%3");
......
...@@ -71,6 +71,8 @@ public: ...@@ -71,6 +71,8 @@ public:
MAV_FRAME getFrame() const { return frame; } MAV_FRAME getFrame() const { return frame; }
MAV_CMD getAction() const { return action; } MAV_CMD getAction() const { return action; }
const QString& getName() const { return name; } const QString& getName() const { return name; }
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
void save(QTextStream &saveStream); void save(QTextStream &saveStream);
bool load(QTextStream &loadStream); bool load(QTextStream &loadStream);
......
...@@ -507,6 +507,22 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList() ...@@ -507,6 +507,22 @@ const QVector<Waypoint *> UASWaypointManager::getGlobalFrameWaypointList()
return wps; 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) int UASWaypointManager::getIndexOf(Waypoint* wp)
{ {
return waypoints.indexOf(wp); return waypoints.indexOf(wp);
...@@ -532,6 +548,26 @@ int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp) ...@@ -532,6 +548,26 @@ int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp)
return -1; 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() int UASWaypointManager::getGlobalFrameCount()
{ {
// Search through all waypoints, // Search through all waypoints,
...@@ -548,6 +584,22 @@ int UASWaypointManager::getGlobalFrameCount() ...@@ -548,6 +584,22 @@ int UASWaypointManager::getGlobalFrameCount()
return i; 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() int UASWaypointManager::getLocalFrameCount()
{ {
// Search through all waypoints, // Search through all waypoints,
......
...@@ -87,11 +87,14 @@ public: ...@@ -87,11 +87,14 @@ public:
/*@{*/ /*@{*/
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the waypoint list. 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 *> 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 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 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 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 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 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 int getLocalFrameCount(); ///< Get the count of local waypoints in the list
/*@}*/ /*@}*/
......
...@@ -111,9 +111,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ...@@ -111,9 +111,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if(serial != 0) if(serial != 0)
{ {
QWidget* conf = new SerialConfigurationWindow(serial, this); QWidget* conf = new SerialConfigurationWindow(serial, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox); //QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf); //layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout); ui.linkScrollArea->setWidget(conf);
//ui.linkScrollArea->setLayout(layout);
ui.linkGroupBox->setTitle(tr("Serial Link")); ui.linkGroupBox->setTitle(tr("Serial Link"));
ui.linkType->setCurrentIndex(0); ui.linkType->setCurrentIndex(0);
//ui.linkGroupBox->setTitle(link->getName()); //ui.linkGroupBox->setTitle(link->getName());
...@@ -123,9 +124,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ...@@ -123,9 +124,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if (udp != 0) if (udp != 0)
{ {
QWidget* conf = new QGCUDPLinkConfiguration(udp, this); QWidget* conf = new QGCUDPLinkConfiguration(udp, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox); //QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf); //layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout); //ui.linkGroupBox->setLayout(layout);
ui.linkScrollArea->setWidget(conf);
ui.linkGroupBox->setTitle(tr("UDP Link")); ui.linkGroupBox->setTitle(tr("UDP Link"));
ui.linkType->setCurrentIndex(1); ui.linkType->setCurrentIndex(1);
} }
...@@ -162,9 +164,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ...@@ -162,9 +164,10 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
if (mavlink != 0) if (mavlink != 0)
{ {
QWidget* conf = new MAVLinkSettingsWidget(mavlink, this); QWidget* conf = new MAVLinkSettingsWidget(mavlink, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.protocolGroupBox); //QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.protocolGroupBox);
layout->addWidget(conf); //layout->addWidget(conf);
ui.protocolGroupBox->setLayout(layout); //ui.protocolGroupBox->setLayout(layout);
ui.protocolScrollArea->setWidget(conf);
ui.protocolGroupBox->setTitle(protocol->getName()+" (Global Settings)"); ui.protocolGroupBox->setTitle(protocol->getName()+" (Global Settings)");
} }
else else
......
...@@ -7,16 +7,19 @@ ...@@ -7,16 +7,19 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>413</width> <width>413</width>
<height>404</height> <height>484</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </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"> <property name="margin">
<number>6</number> <number>6</number>
</property> </property>
<property name="spacing">
<number>6</number>
</property>
<item row="0" column="0"> <item row="0" column="0">
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
...@@ -28,7 +31,7 @@ ...@@ -28,7 +31,7 @@
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>5</width> <width>5</width>
<height>10</height> <height>5</height>
</size> </size>
</property> </property>
</spacer> </spacer>
...@@ -73,6 +76,31 @@ ...@@ -73,6 +76,31 @@
<property name="title"> <property name="title">
<string>Link</string> <string>Link</string>
</property> </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> </widget>
</item> </item>
<item row="4" column="0" colspan="2"> <item row="4" column="0" colspan="2">
...@@ -80,6 +108,31 @@ ...@@ -80,6 +108,31 @@
<property name="title"> <property name="title">
<string>Protocol</string> <string>Protocol</string>
</property> </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> </widget>
</item> </item>
<item row="5" column="0"> <item row="5" column="0">
...@@ -97,6 +150,9 @@ ...@@ -97,6 +150,9 @@
</item> </item>
<item row="5" column="1"> <item row="5" column="1">
<layout class="QHBoxLayout" name="horizontalLayout"> <layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="sizeConstraint"> <property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum> <enum>QLayout::SetDefaultConstraint</enum>
</property> </property>
......
...@@ -172,6 +172,9 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -172,6 +172,9 @@ MainWindow::MainWindow(QWidget *parent):
LinkManager::instance()->addProtocol(link, mavlink); LinkManager::instance()->addProtocol(link, mavlink);
link->connect(); link->connect();
} }
// Initialize window state
windowStateVal = windowState();
} }
MainWindow::~MainWindow() MainWindow::~MainWindow()
...@@ -1810,6 +1813,11 @@ void MainWindow::UASCreated(UASInterface* uas) ...@@ -1810,6 +1813,11 @@ void MainWindow::UASCreated(UASInterface* uas)
// Custom widgets, added last to all menus and layouts // Custom widgets, added last to all menus and layouts
buildCustomWidget(); buildCustomWidget();
// Restore the mainwindow size
if (settings.contains(getWindowGeometryKey()))
{
restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
}
} }
/** /**
...@@ -1819,6 +1827,10 @@ void MainWindow::clearView() ...@@ -1819,6 +1827,10 @@ void MainWindow::clearView()
{ {
// Save current state // Save current state
if (UASManager::instance()->getUASList().count() > 0) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion())); if (UASManager::instance()->getUASList().count() > 0) settings.setValue(getWindowStateKey(), saveState(QGC::applicationVersion()));
// Although we want save the state of the window, we do not want to change the top-leve state (minimized, maximized, etc)
// therefore this state is stored here and restored after applying the rest of the settings in the new
// perspective.
windowStateVal = this->windowState();
settings.setValue(getWindowGeometryKey(), saveGeometry()); settings.setValue(getWindowGeometryKey(), saveGeometry());
QAction* temp; QAction* temp;
...@@ -2028,11 +2040,11 @@ void MainWindow::presentView() ...@@ -2028,11 +2040,11 @@ void MainWindow::presentView()
// Restore window state // Restore window state
if (UASManager::instance()->getUASList().count() > 0) if (UASManager::instance()->getUASList().count() > 0)
{ {
// Restore the mainwindow size // // Restore the mainwindow size
if (settings.contains(getWindowGeometryKey())) // if (settings.contains(getWindowGeometryKey()))
{ // {
restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray()); // restoreGeometry(settings.value(getWindowGeometryKey()).toByteArray());
} // }
// Restore the widget positions and size // Restore the widget positions and size
if (settings.contains(getWindowStateKey())) if (settings.contains(getWindowStateKey()))
...@@ -2051,6 +2063,7 @@ void MainWindow::presentView() ...@@ -2051,6 +2063,7 @@ void MainWindow::presentView()
} }
} }
this->setWindowState(windowStateVal);
this->show(); this->show();
} }
......
...@@ -426,6 +426,7 @@ protected: ...@@ -426,6 +426,7 @@ protected:
QString styleFileName; QString styleFileName;
bool autoReconnect; bool autoReconnect;
QGC_MAINWINDOW_STYLE currentStyle; QGC_MAINWINDOW_STYLE currentStyle;
Qt::WindowStates windowStateVal;
private: private:
Ui::MainWindow ui; Ui::MainWindow ui;
......
...@@ -130,6 +130,9 @@ ...@@ -130,6 +130,9 @@
<addaction name="separator"/> <addaction name="separator"/>
<addaction name="actionMavlinkView"/> <addaction name="actionMavlinkView"/>
<addaction name="actionUnconnectedView"/> <addaction name="actionUnconnectedView"/>
<addaction name="separator"/>
<addaction name="actionFullscreen"/>
<addaction name="actionNormal"/>
</widget> </widget>
<widget class="QMenu" name="menuMain"> <widget class="QMenu" name="menuMain">
<property name="title"> <property name="title">
...@@ -437,6 +440,22 @@ ...@@ -437,6 +440,22 @@
<string>Settings</string> <string>Settings</string>
</property> </property>
</action> </action>
<action name="actionFullscreen">
<property name="text">
<string>Fullscreen</string>
</property>
<property name="shortcut">
<string>Meta+Return</string>
</property>
</action>
<action name="actionNormal">
<property name="text">
<string>Normal</string>
</property>
<property name="shortcut">
<string>Esc</string>
</property>
</action>
</widget> </widget>
<layoutdefault spacing="6" margin="11"/> <layoutdefault spacing="6" margin="11"/>
<resources> <resources>
...@@ -459,5 +478,37 @@ ...@@ -459,5 +478,37 @@
</hint> </hint>
</hints> </hints>
</connection> </connection>
<connection>
<sender>actionFullscreen</sender>
<signal>triggered()</signal>
<receiver>MainWindow</receiver>
<slot>showFullScreen()</slot>
<hints>
<hint type="sourcelabel">
<x>-1</x>
<y>-1</y>
</hint>
<hint type="destinationlabel">
<x>399</x>
<y>249</y>
</hint>
</hints>
</connection>
<connection>
<sender>actionNormal</sender>
<signal>triggered()</signal>
<receiver>MainWindow</receiver>
<slot>showNormal()</slot>
<hints>
<hint type="sourcelabel">
<x>-1</x>
<y>-1</y>
</hint>
<hint type="destinationlabel">
<x>399</x>
<y>249</y>
</hint>
</hints>
</connection>
</connections> </connections>
</ui> </ui>
...@@ -557,14 +557,14 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView) ...@@ -557,14 +557,14 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
if (uas == this->mav->getUASID()) if (uas == this->mav->getUASID())
{ {
// Only accept waypoints in global coordinate frame // 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 // We're good, this is a global waypoint
// Get the index of this waypoint // Get the index of this waypoint
// note the call to getGlobalFrameIndexOf() // note the call to getGlobalFrameAndNavTypeIndexOf()
// as we're only handling global waypoints // 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 not found, return (this should never happen, but helps safety)
if (wpindex == -1) return; if (wpindex == -1) return;
...@@ -623,7 +623,7 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView) ...@@ -623,7 +623,7 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
// waypoint list. This implies that the coordinate frame of this // waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global // waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list // 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); updateWaypointList(uas);
} }
...@@ -724,7 +724,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate) ...@@ -724,7 +724,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
// Update waypoint data storage // Update waypoint data storage
if (mav) if (mav)
{ {
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList(); QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
if (wps.size() > index) if (wps.size() > index)
{ {
...@@ -836,7 +836,7 @@ void MapWidget::updateWaypointList(int uas) ...@@ -836,7 +836,7 @@ void MapWidget::updateWaypointList(int uas)
} }
// Trim internal list to number of global waypoints in the waypoint manager list // 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) if (overSize > 0)
{ {
// Remove n waypoints at the end of the list // Remove n waypoints at the end of the list
......
...@@ -6,14 +6,14 @@ ...@@ -6,14 +6,14 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>449</width> <width>304</width>
<height>250</height> <height>283</height>
</rect> </rect>
</property> </property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </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"> <property name="margin">
<number>6</number> <number>6</number>
</property> </property>
...@@ -284,13 +284,6 @@ ...@@ -284,13 +284,6 @@
</item> </item>
</layout> </layout>
</item> </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"> <item row="4" column="1">
<widget class="QSpinBox" name="dataBitsSpinBox"> <widget class="QSpinBox" name="dataBitsSpinBox">
<property name="sizePolicy"> <property name="sizePolicy">
...@@ -373,12 +366,19 @@ ...@@ -373,12 +366,19 @@
</property> </property>
<property name="sizeHint" stdset="0"> <property name="sizeHint" stdset="0">
<size> <size>
<width>431</width> <width>0</width>
<height>47</height> <height>0</height>
</size> </size>
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="4" column="0">
<widget class="QLabel" name="portlabel_5">
<property name="text">
<string>Data bits</string>
</property>
</widget>
</item>
</layout> </layout>
<action name="actionDelete"> <action name="actionDelete">
<property name="text"> <property name="text">
......
...@@ -234,14 +234,14 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas) ...@@ -234,14 +234,14 @@ void QGCGoogleEarthView::setActiveUAS(UASInterface* uas)
void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp) void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{ {
// Only accept waypoints in global coordinate frame // 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 // We're good, this is a global waypoint
// Get the index of this waypoint // Get the index of this waypoint
// note the call to getGlobalFrameIndexOf() // note the call to getGlobalFrameAndNavTypeIndexOf()
// as we're only handling global waypoints // 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 not found, return (this should never happen, but helps safety)
if (wpindex == -1) if (wpindex == -1)
{ {
...@@ -267,7 +267,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas) ...@@ -267,7 +267,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
if (uasInstance) if (uasInstance)
{ {
// Get all waypoints, including non-global waypoints // 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 // Trim internal list to number of global waypoints in the waypoint manager list
javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count())); javaScript(QString("updateWaypointListLength(%1,%2);").arg(uas).arg(wpList.count()));
...@@ -741,7 +741,7 @@ void QGCGoogleEarthView::updateState() ...@@ -741,7 +741,7 @@ void QGCGoogleEarthView::updateState()
// Update waypoint or symbol // Update waypoint or symbol
if (mav) if (mav)
{ {
QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameWaypointList(); QVector<Waypoint*> wps = mav->getWaypointManager()->getGlobalFrameAndNavTypeWaypointList();
bool ok; bool ok;
int index = idText.toInt(&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