Commit 43918649 authored by pixhawk's avatar pixhawk

Merge branch 'master' of pixhawk.ethz.ch:qgroundcontrol

parents 15058112 26d325fe
......@@ -44,3 +44,4 @@ user_config.pri
*.cproject
*.sln
*.suo
*thirdParty*
......@@ -75,15 +75,13 @@ endif(NOT CMAKE_BUILD_TYPE)
enable_language(C)
enable_language(CXX)
# initialize variables
set(qgroundcontrol_LIBRARIES qgroundcontrolNavigation qgroundcontrolCommunication)
set(SCICOSLAB_BLOCKS stdBlocks;jsbsimBlocks;mavlinkBlocks)
# installer
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_GENERATOR "DEB")
set(CPACK_SOURCE_GENERATOR "TGZ;ZIP")
set(CPACK_SOURCE_GENERATOR "TGZ")
set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
set(CPACK_SET_DESTDIR TRUE)
set(CPACK_PACKAGE_CONTACT "James Goppert james.goppert@gmail.com")
......@@ -93,7 +91,8 @@ set(CPACK_PACKAGE_DESCRITION_SUMMARY "
A qt based ground-control program for unmanned systems.
")
set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES}
/.git/;/build/;~$;.*\\\\.bin$;.*\\\\.swp$)
"/.git/";"/build/";"~$";".*\\\\.bin$";".*\\\\.swp$"
)
set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_SOURCE_DIR}/license.txt")
set(CPACK_RESOURCE_FILE_README "${CMAKE_SOURCE_DIR}/README")
set(CPACK_PACKAGE_VERSION_MAJOR ${qgroundcontrol_VERSION_MAJOR})
......@@ -125,7 +124,13 @@ if (UNIX)
find_package(Flite)
endif(UNIX)
find_package(OpenGL REQUIRED)
find_package(OpenSceneGraph 2.8.3 COMPONENTS osgGA osgDB osgUtil osgViewer)
find_package(OpenSceneGraph 2.9.9 COMPONENTS osgGA osgDB osgUtil osgViewer)
if ("OSG_LIBRARY-NOTFOUND" STREQUAL "${OSG_LIBRARY}")
set(OPENSCENEGRAPH_FOUND FALSE)
else()
set(OPENSCENEGRAPH_FOUND TRUE)
endif()
find_or_build_from_source(MAVLINK thirdParty/mavlink FOUND_GIT_REPO)
# build libraries from source if not found on system
......@@ -184,6 +189,7 @@ set(qgroundcontrolIncludes
lib/QMapControl
${PROJECT_BINARY_DIR}
)
set (qgroundcontrolLibs)
# dependency summary
message(STATUS "=======================================")
......@@ -191,52 +197,49 @@ message(STATUS "\tDEPENDENCY\t\tFOUND")
message(STATUS "=======================================")
# common dependencies
message(STATUS "\t\tMAVLINK\t\t${MAVLINK_FOUND}")
if (MAVLINK_FOUND)
message(STATUS "\t\tMAVLINK\t\tYES")
list(APPEND qgroundcontrolIncludes ${MAVLINK_INCLUDE_DIRS})
else()
message(STATUS "\t\tOpenSceneGraph\t\tNO")
endif (MAVLINK_FOUND)
endif()
message(STATUS "\t\tOpenSceneGraph\t${OPENSCENEGRAPH_FOUND}")
if (OPENSCENEGRAPH_FOUND)
message(STATUS "\t\tOpenSceneGraph\tYES")
list(APPEND qgroundcontrolIncludes ${OPENSCENEGRAPH_INCLUDE_DIRS})
else()
message(STATUS "\t\tOpenSceneGraph\t\tNO")
endif (OPENSCENEGRAPH_FOUND)
list(APPEND qgroundcontrolLibs ${OPENSCENEGRAPH_LIBRARIES})
endif()
message(STATUS "\t\tQT4\t\t${QT4_FOUND}")
if (QT4_FOUND)
message(STATUS "\t\tQT4\t\tYES")
list(APPEND qgroundcontrolIncludes ${QT_INCLUDE_DIRS})
else()
message(STATUS "\t\tQT4\t\tNO")
endif (QT4_FOUND)
list(APPEND qgroundcontrolLibs ${QT_LIBRARIES})
endif()
message(STATUS "\t\tPHONON\t\t${PHONON_FOUND}")
if (PHONON_FOUND)
message(STATUS "\t\tPHONON\t\tYES")
list(APPEND qgroundcontrolIncludes ${PHONON_INCLUDE_DIR}/phonon)
else()
message(STATUS "\t\tPHONON\t\tNO")
endif (PHONON_FOUND)
list(APPEND qgroundcontrolIncludes ${PHONON_INCLUDES})
list(APPEND qgroundcontrolLibs ${PHONON_LIBS})
endif()
message(STATUS "\t\tSDL\t\t${SDL_FOUND}")
if (SDL_FOUND)
message(STATUS "\t\tSDL\t\tYES")
list(APPEND qgroundcontrolIncludes ${SDL_INCLUDE_DIR})
else()
message(STATUS "\t\tSDL\t\tNO")
endif (SDL_FOUND)
list(APPEND qgroundcontrolLibs ${SDL_LIBRARY})
endif()
message(STATUS "\t\tOPENGL\t\t${OPENGL_FOUND}")
if (OPENGL_FOUND)
message(STATUS "\t\tOPENGL\t\tYES")
list(APPEND qgroundcontrolIncludes ${OPENGL_INCLUDE_DIR})
else()
message(STATUS "\t\tOPENGL\t\tNO")
endif (OPENGL_FOUND)
list(APPEND qgroundcontrolLibs ${OPENGL_LIBRARIES})
endif()
# unix only dependencies
if (UNIX)
message(STATUS "\t\tFLITE\t\t${FLITE_FOUND}")
if (FLITE_FOUND)
message(STATUS "\t\tFLITE\t\tYES")
list(APPEND qgroundcontrolIncludes ${FLITE_INCLUDE_DIR})
else()
message(STATUS "\t\tFLITE\t\tNO")
endif (FLITE_FOUND)
endif(UNIX)
list(APPEND qgroundcontrolLibs ${FLITE_LIBRARIES})
endif ()
endif()
# set include directories
include_directories(${qgroundcontrolIncludes})
......@@ -270,6 +273,7 @@ set(qgroundcontrolUiSrc
src/ui/HDDisplay.ui
src/ui/MAVLinkSettingsWidget.ui
src/ui/AudioOutputWidget.ui
src/ui/designer/QGCCommandButton.ui
src/ui/QGCSensorSettingsWidget.ui
src/ui/watchdog/WatchdogControl.ui
src/ui/watchdog/WatchdogProcessView.ui
......@@ -392,6 +396,7 @@ set(qgroundcontrolMocSrc
src/ui/map3D/QGCWebPage.h
src/ui/ObjectDetectionView.h
src/ui/SerialConfigurationWindow.h
src/ui/designer/QGCCommandButton.h
src/ui/QGCFirmwareUpdate.h
src/ui/CommConfigurationWindow.h
src/ui/MAVLinkSettingsWidget.h
......@@ -496,6 +501,7 @@ set (qgroundcontrolSrc
src/ui/ObjectDetectionView.cc
src/ui/ParameterInterface.cc
src/ui/QGCDataPlot2D.cc
src/ui/designer/QGCCommandButton.cc
src/ui/QGCFirmwareUpdate.cc
src/ui/QGCMAVLinkLogPlayer.cc
src/ui/QGCMainWindowAPConfigurator.cc
......@@ -562,12 +568,7 @@ add_executable(qgroundcontrol
)
add_dependencies(qgroundcontrol MAVLINK)
target_link_libraries(qgroundcontrol
${SDL_LIBRARY}
${OPENGL_LIBRARIES}
${OSG_LIBRARIES}
${QT_LIBRARIES}
${FLITE_LIBRARIES}
${PHONON_LIBS}
${qgroundcontrolLibs}
qextserialport qmapcontrol qwt)
# qgroundcontrol install
......
......@@ -19,53 +19,19 @@ macro(_phonon_find_version)
file(READ ${_phonon_namespace_header_file} _phonon_header LIMIT 5000 OFFSET 1000)
string(REGEX MATCH "define PHONON_VERSION_STR \"(4\\.[0-9]+\\.[0-9a-z]+)\"" _phonon_version_match "${_phonon_header}")
set(PHONON_VERSION "${CMAKE_MATCH_1}")
message(STATUS "Phonon Version: ${PHONON_VERSION}")
endmacro(_phonon_find_version)
if(PHONON_FOUND)
# Already found, nothing more to do except figuring out the version
_phonon_find_version()
else(PHONON_FOUND)
if(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
set(PHONON_FIND_QUIETLY TRUE)
endif(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
# As discussed on kde-buildsystem: first look at CMAKE_PREFIX_PATH, then at the suggested PATHS (kde4 install dir)
find_library(PHONON_LIBRARY NAMES phonon phonon4 PATHS /usr/lib ${KDE4_LIB_INSTALL_DIR} ${QT_LIBRARY_DIR})
# then at the default system locations (CMAKE_SYSTEM_PREFIX_PATH, i.e. /usr etc.)
find_library(PHONON_LIBRARY NAMES phonon phonon4)
find_path(PHONON_INCLUDE_DIR NAMES phonon/phonon_export.h PATHS /usr/include ${KDE4_INCLUDE_INSTALL_DIR} ${QT_INCLUDE_DIR} ${INCLUDE_INSTALL_DIR} ${QT_LIBRARY_DIR})
find_path(PHONON_INCLUDE_DIR NAMES phonon/phonon_export.h)
# the dirs listed with HINTS are searched before the default sets of dirs
find_library(PHONON_LIBRARY NAMES phonon HINTS ${KDE4_LIB_INSTALL_DIR} ${QT_LIBRARY_DIR})
find_path(PHONON_INCLUDE_DIR NAMES phonon/phonon_export.h HINTS ${KDE4_INCLUDE_INSTALL_DIR} ${QT_INCLUDE_DIR} ${INCLUDE_INSTALL_DIR} ${QT_LIBRARY_DIR})
if(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
set(PHONON_LIBS ${phonon_LIB_DEPENDS} ${PHONON_LIBRARY})
set(PHONON_INCLUDES ${PHONON_INCLUDE_DIR}/KDE ${PHONON_INCLUDE_DIR})
set(PHONON_FOUND TRUE)
_phonon_find_version()
else(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
set(PHONON_FOUND FALSE)
endif(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
if(PHONON_FOUND)
if(NOT PHONON_FIND_QUIETLY)
message(STATUS "Found Phonon: ${PHONON_LIBRARY}")
message(STATUS "Found Phonon Includes: ${PHONON_INCLUDES}")
endif(NOT PHONON_FIND_QUIETLY)
else(PHONON_FOUND)
if(Phonon_FIND_REQUIRED)
if(NOT PHONON_INCLUDE_DIR)
message(STATUS "Phonon includes NOT found!")
endif(NOT PHONON_INCLUDE_DIR)
if(NOT PHONON_LIBRARY)
message(STATUS "Phonon library NOT found!")
endif(NOT PHONON_LIBRARY)
message(FATAL_ERROR "Phonon library or includes NOT found!")
else(Phonon_FIND_REQUIRED)
message(STATUS "Unable to find Phonon")
endif(Phonon_FIND_REQUIRED)
endif(PHONON_FOUND)
if(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
set(PHONON_LIBS ${phonon_LIB_DEPENDS} ${PHONON_LIBRARY})
set(PHONON_INCLUDES ${PHONON_INCLUDE_DIR}/phonon ${PHONON_INCLUDE_DIR}/KDE ${PHONON_INCLUDE_DIR})
_phonon_find_version()
endif(PHONON_INCLUDE_DIR AND PHONON_LIBRARY)
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(Phonon DEFAULT_MSG PHONON_INCLUDE_DIR PHONON_LIBRARY)
mark_as_advanced(PHONON_INCLUDE_DIR PHONON_LIBRARY PHONON_INCLUDES)
endif(PHONON_FOUND)
mark_as_advanced(PHONON_INCLUDE_DIR PHONON_LIBRARY)
......@@ -362,7 +362,6 @@ function updateWaypoint(id, index, lat, lon, alt, action)
location.setAltitude(alt);
waypoints[index].setGeometry(location);
waypoints[index].setDescription(index+"");
console.log('WP LOC:' + lat + lon + alt);
}
else
{
......@@ -373,7 +372,7 @@ function updateWaypoint(id, index, lat, lon, alt, action)
if (index < 10) numberstring = '0' + numberstring
icon.setHref('http://google-maps-icons.googlecode.com/files/red' + numberstring +'.png');
var style = ge.createStyle('');
console.log('WP ICON created:' + 'http://google-maps-icons.googlecode.com/files/red' + numberstring +'.png');
//console.log('WP ICON created:' + 'http://google-maps-icons.googlecode.com/files/red' + numberstring +'.png');
style.getIconStyle().setIcon(icon);
//style.getIconStyle().setScale(0.5);
placemark.setStyleSelector(style);
......@@ -424,7 +423,7 @@ function createAircraft(id, type, color)
//planeColor = color;
createTrail(id, color);
console.log(color);
//console.log(color);
}
function createTrail(id, color)
......
......@@ -86,6 +86,13 @@ border: 1px solid #777777;
QMainWindow::separator:hover {
background: white;
}
QGCToolWidgetItem {
border: 1px solid #66666B;
border-radius: 3px;
padding: 10px 0px 0px 0px;
margin-top: 1ex; /* leave space at the top for the title */
}
QDockWidget {
border: 1px solid #32345E;
......
......@@ -153,6 +153,7 @@ FORMS += src/ui/MainWindow.ui \
src/ui/designer/QGCToolWidget.ui \
src/ui/designer/QGCParamSlider.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
......@@ -264,6 +265,7 @@ HEADERS += src/MG.h \
src/ui/designer/QGCToolWidget.h \
src/ui/designer/QGCParamSlider.h \
src/ui/designer/QGCActionButton.h \
src/ui/designer/QGCCommandButton.h \
src/ui/designer/QGCToolWidgetItem.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
......@@ -394,6 +396,7 @@ SOURCES += src/main.cc \
src/ui/designer/QGCToolWidget.cc \
src/ui/designer/QGCParamSlider.cc \
src/ui/designer/QGCActionButton.cc \
src/ui/designer/QGCCommandButton.cc \
src/ui/designer/QGCToolWidgetItem.cc \
src/ui/QGCMAVLinkLogPlayer.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
......
......@@ -36,7 +36,8 @@ This file is part of the PIXHAWK project
#include <QTimer>
#include <QStringList>
#ifdef Q_OS_MAC
#include <Phonon>
#include <MediaObject>
#include <AudioOutput>
#endif
#ifdef Q_OS_LINUX
//#include <flite/flite.h>
......
......@@ -29,8 +29,10 @@ This file is part of the QGROUNDCONTROL project
*
*/
#include "Waypoint.h"
#include <QStringList>
#include <QDebug>
#include "Waypoint.h"
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1, double _param2, double _param3, double _param4,
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action)
......@@ -55,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");
......@@ -229,6 +236,8 @@ void Waypoint::setAcceptanceRadius(double radius)
void Waypoint::setParam1(double param1)
{
qDebug() << "SENDER:" << QObject::sender();
qDebug() << "PARAM1 SET REQ:" << param1;
if (this->param1 != param1)
{
this->param1 = param1;
......
......@@ -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);
......
......@@ -1059,7 +1059,6 @@ void UAS::setHomePosition(double lat, double lon, double alt)
void UAS::setLocalOriginAtCurrentGPSPosition()
{
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
......@@ -1766,6 +1765,38 @@ void UAS::setUASName(const QString& name)
emit systemSpecsChanged(uasId);
}
void UAS::executeCommand(MAV_CMD command)
{
mavlink_message_t msg;
mavlink_command_t cmd;
cmd.command = (uint8_t)command;
cmd.confirmation = 0;
cmd.param1 = 0.0f;
cmd.param2 = 0.0f;
cmd.param3 = 0.0f;
cmd.param4 = 0.0f;
cmd.target_system = uasId;
cmd.target_component = 0;
mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component)
{
mavlink_message_t msg;
mavlink_command_t cmd;
cmd.command = (uint8_t)command;
cmd.confirmation = confirmation;
cmd.param1 = param1;
cmd.param2 = param2;
cmd.param3 = param3;
cmd.param4 = param4;
cmd.target_system = uasId;
cmd.target_component = component;
mavlink_msg_command_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
sendMessage(msg);
}
/**
* Sets an action
*
......
......@@ -214,6 +214,10 @@ public slots:
void setUASName(const QString& name);
/** @brief Executes an action **/
void setAction(MAV_ACTION action);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component);
/** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */
......
......@@ -189,6 +189,10 @@ public slots:
virtual void setUASName(const QString& name) = 0;
/** @brief Sets an action **/
virtual void setAction(MAV_ACTION action) = 0;
/** @brief Execute command immediately **/
virtual void executeCommand(MAV_CMD command) = 0;
/** @brief Executes a command **/
virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component) = 0;
/** @brief Selects the airframe */
virtual void setAirframe(int airframe) = 0;
......
......@@ -512,6 +512,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);
......@@ -537,6 +553,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,
......@@ -553,6 +589,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>
......
......@@ -307,9 +307,11 @@ void MainWindow::buildCustomWidget()
if (!dock)
{
QDockWidget* dock = new QDockWidget(widgets.at(i)->windowTitle(), this);
dock->setObjectName(widgets.at(i)->objectName()+"_DOCK");
dock->setWidget(widgets.at(i));
connect(widgets.at(i), SIGNAL(destroyed()), dock, SLOT(deleteLater()));
QAction* showAction = new QAction(widgets.at(i)->windowTitle(), this);
showAction->setCheckable(true);
connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool)));
connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool)));
widgets.at(i)->setMainMenuAction(showAction);
......@@ -1045,6 +1047,7 @@ void MainWindow::createCustomWidget()
connect(tool, SIGNAL(destroyed()), dock, SLOT(deleteLater()));
dock->setWidget(tool);
QAction* showAction = new QAction("Show Unnamed Tool", this);
showAction->setCheckable(true);
connect(dock, SIGNAL(visibilityChanged(bool)), showAction, SLOT(setChecked(bool)));
connect(showAction, SIGNAL(triggered(bool)), dock, SLOT(setVisible(bool)));
tool->setMainMenuAction(showAction);
......
......@@ -130,6 +130,9 @@
<addaction name="separator"/>
<addaction name="actionMavlinkView"/>
<addaction name="actionUnconnectedView"/>
<addaction name="separator"/>
<addaction name="actionFullscreen"/>
<addaction name="actionNormal"/>
</widget>
<widget class="QMenu" name="menuMain">
<property name="title">
......@@ -437,6 +440,22 @@
<string>Settings</string>
</property>
</action>
<action name="actionFullscreen">
<property name="text">
<string>Fullscreen</string>
</property>
<property name="shortcut">
<string>Alt+Return</string>
</property>
</action>
<action name="actionNormal">
<property name="text">
<string>Normal</string>
</property>
<property name="shortcut">
<string>Esc</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......@@ -459,5 +478,37 @@
</hint>
</hints>
</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>
</ui>
......@@ -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">
......
......@@ -43,10 +43,10 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("NAV: Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND);
m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
// m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
//m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
//m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
//m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// add frames
......@@ -203,7 +203,7 @@ void WaypointView::updateActionView(int action)
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
break;
case MAV_CMD_NAV_TARGET:
case MAV_CMD_NAV_ORIENTATION_TARGET:
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->turnsSpinBox->hide();
......@@ -261,6 +261,7 @@ void WaypointView::changedAction(int index)
void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
{
viewMode = mode;
switch (mode)
{
case QGC_WAYPOINTVIEW_MODE_NAV:
......@@ -285,6 +286,9 @@ void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
int action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
m_ui->comboBox_action->setCurrentIndex(action_index);
// Show action widget
if (!m_ui->customActionWidget->isVisible())
{
......@@ -296,6 +300,7 @@ void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
}
break;
}
}
void WaypointView::updateFrameView(int frame)
......@@ -438,9 +443,12 @@ void WaypointView::updateValues()
}
else
{
// Action ID known, update
m_ui->comboBox_action->setCurrentIndex(action_index);
updateActionView(action);
if (viewMode != QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING)
{
// Action ID known, update
m_ui->comboBox_action->setCurrentIndex(action_index);
updateActionView(action);
}
}
}
switch(action)
......@@ -459,7 +467,9 @@ void WaypointView::updateValues()
if (m_ui->yawSpinBox->value() != wp->getYaw())
{
if (!m_ui->yawSpinBox->isVisible()) m_ui->yawSpinBox->blockSignals(true);
m_ui->yawSpinBox->setValue(wp->getYaw());
if (!m_ui->yawSpinBox->isVisible()) m_ui->yawSpinBox->blockSignals(false);
}
if (m_ui->selectedBox->isChecked() != wp->getCurrent())
{
......@@ -472,23 +482,33 @@ void WaypointView::updateValues()
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));
if (m_ui->orbitSpinBox->value() != wp->getLoiterOrbit())
{
if (!m_ui->orbitSpinBox->isVisible()) m_ui->orbitSpinBox->blockSignals(true);
m_ui->orbitSpinBox->setValue(wp->getLoiterOrbit());
if (!m_ui->orbitSpinBox->isVisible()) m_ui->orbitSpinBox->blockSignals(false);
}
if (m_ui->acceptanceSpinBox->value() != wp->getAcceptanceRadius())
{
if (!m_ui->acceptanceSpinBox->isVisible()) m_ui->acceptanceSpinBox->blockSignals(true);
m_ui->acceptanceSpinBox->setValue(wp->getAcceptanceRadius());
if (!m_ui->acceptanceSpinBox->isVisible()) m_ui->acceptanceSpinBox->blockSignals(false);
}
if (m_ui->holdTimeSpinBox->value() != wp->getHoldTime())
{
if (!m_ui->holdTimeSpinBox->isVisible()) m_ui->holdTimeSpinBox->blockSignals(true);
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
if (!m_ui->holdTimeSpinBox->isVisible()) m_ui->holdTimeSpinBox->blockSignals(false);
}
if (m_ui->turnsSpinBox->value() != wp->getTurns())
{
if (!m_ui->turnsSpinBox->isVisible()) m_ui->turnsSpinBox->blockSignals(true);
m_ui->turnsSpinBox->setValue(wp->getTurns());
if (!m_ui->turnsSpinBox->isVisible()) m_ui->turnsSpinBox->blockSignals(false);
}
if (m_ui->takeOffAngleSpinBox->value() != wp->getParam1())
{
if (!m_ui->takeOffAngleSpinBox->isVisible()) m_ui->takeOffAngleSpinBox->blockSignals(true);
m_ui->takeOffAngleSpinBox->setValue(wp->getParam1());
if (!m_ui->takeOffAngleSpinBox->isVisible()) m_ui->takeOffAngleSpinBox->blockSignals(false);
}
// UPDATE CUSTOM ACTION WIDGET
......
......@@ -14,6 +14,18 @@
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="100,100,50">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<item row="1" column="0" colspan="2">
<widget class="QLabel" name="nameLabel">
<property name="minimumSize">
......
#include "QGCCommandButton.h"
#include "ui_QGCCommandButton.h"
#include "MAVLinkProtocol.h"
#include "UASManager.h"
QGCCommandButton::QGCCommandButton(QWidget *parent) :
QGCToolWidgetItem("Command Button", parent),
ui(new Ui::QGCCommandButton),
uas(NULL)
{
ui->setupUi(this);
connect(ui->commandButton, SIGNAL(clicked()), this, SLOT(sendCommand()));
connect(ui->editFinishButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
connect(ui->editButtonName, SIGNAL(textChanged(QString)), this, SLOT(setCommandButtonName(QString)));
connect(ui->editCommandComboBox, SIGNAL(currentIndexChanged(QString)), ui->nameLabel, SLOT(setText(QString)));
// Hide all edit items
ui->editCommandComboBox->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
ui->editConfirmationCheckBox->hide();
ui->editComponentSpinBox->hide();
ui->editParamsVisibleCheckBox->hide();
ui->editParam1SpinBox->hide();
ui->editParam2SpinBox->hide();
ui->editParam3SpinBox->hide();
ui->editParam4SpinBox->hide();
ui->editLine1->hide();
ui->editLine2->hide();
ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
// Add commands to combo box
ui->editCommandComboBox->addItem("DO: Control Video", MAV_CMD_DO_CONTROL_VIDEO);
ui->editCommandComboBox->addItem("PREFLIGHT: Calibration", MAV_CMD_PREFLIGHT_CALIBRATION);
}
QGCCommandButton::~QGCCommandButton()
{
delete ui;
}
void QGCCommandButton::sendCommand()
{
if (QGCToolWidgetItem::uas)
{
// FIXME
int index = ui->editCommandComboBox->itemData(ui->editCommandComboBox->currentIndex()).toInt();
MAV_CMD command = static_cast<MAV_CMD>(index);
int confirm = (ui->editConfirmationCheckBox->isChecked()) ? 1 : 0;
float param1 = ui->editParam1SpinBox->value();
float param2 = ui->editParam2SpinBox->value();
float param3 = ui->editParam3SpinBox->value();
float param4 = ui->editParam4SpinBox->value();
int component = ui->editComponentSpinBox->value();
QGCToolWidgetItem::uas->executeCommand(command, confirm, param1, param2, param3, param4, component);
}
else
{
qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING";
}
}
void QGCCommandButton::setCommandButtonName(QString text)
{
ui->commandButton->setText(text);
}
void QGCCommandButton::startEditMode()
{
// Hide elements
ui->commandButton->hide();
ui->nameLabel->hide();
ui->editCommandComboBox->show();
ui->editFinishButton->show();
ui->editNameLabel->show();
ui->editButtonName->show();
ui->editConfirmationCheckBox->show();
ui->editComponentSpinBox->show();
ui->editParamsVisibleCheckBox->show();
ui->editParam1SpinBox->show();
ui->editParam2SpinBox->show();
ui->editParam3SpinBox->show();
ui->editParam4SpinBox->show();
ui->editLine1->show();
ui->editLine2->show();
//setStyleSheet("QGroupBox { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
isInEditMode = true;
}
void QGCCommandButton::endEditMode()
{
ui->editCommandComboBox->hide();
ui->editFinishButton->hide();
ui->editNameLabel->hide();
ui->editButtonName->hide();
ui->editConfirmationCheckBox->hide();
ui->editComponentSpinBox->hide();
ui->editParamsVisibleCheckBox->hide();
ui->editLine1->hide();
ui->editLine2->hide();
if (!ui->editParamsVisibleCheckBox->isChecked())
{
ui->editParam1SpinBox->hide();
ui->editParam2SpinBox->hide();
ui->editParam3SpinBox->hide();
ui->editParam4SpinBox->hide();
}
ui->commandButton->show();
ui->nameLabel->show();
// Write to settings
emit editingFinished();
//setStyleSheet("");
isInEditMode = false;
}
void QGCCommandButton::writeSettings(QSettings& settings)
{
settings.setValue("TYPE", "COMMANDBUTTON");
settings.setValue("QGC_ACTION_BUTTON_DESCRIPTION", ui->nameLabel->text());
settings.setValue("QGC_ACTION_BUTTON_BUTTONTEXT", ui->commandButton->text());
settings.setValue("QGC_ACTION_BUTTON_ACTIONID", ui->editCommandComboBox->currentIndex());
settings.setValue("QGC_COMMAND_BUTTON_PARAMS_VISIBLE", ui->editParamsVisibleCheckBox->isChecked());
settings.sync();
}
void QGCCommandButton::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->editCommandComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
ui->nameLabel->setText(settings.value("QGC_ACTION_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
ui->commandButton->setText(settings.value("QGC_ACTION_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
ui->editCommandComboBox->setCurrentIndex(settings.value("QGC_ACTION_BUTTON_ACTIONID", 0).toInt());
ui->editParamsVisibleCheckBox->setChecked(settings.value("QGC_COMMAND_BUTTON_PARAMS_VISIBLE").toBool());
if (ui->editParamsVisibleCheckBox->isChecked())
{
ui->editParam1SpinBox->show();
ui->editParam2SpinBox->show();
ui->editParam3SpinBox->show();
ui->editParam4SpinBox->show();
}
else
{
ui->editParam1SpinBox->hide();
ui->editParam2SpinBox->hide();
ui->editParam3SpinBox->hide();
ui->editParam4SpinBox->hide();
}
qDebug() << "DONE READING SETTINGS";
}
#ifndef QGCCOMMANDBUTTON_H
#define QGCCOMMANDBUTTON_H
#include "QGCToolWidgetItem.h"
namespace Ui {
class QGCCommandButton;
}
class UASInterface;
class QGCCommandButton : public QGCToolWidgetItem
{
Q_OBJECT
public:
explicit QGCCommandButton(QWidget *parent = 0);
~QGCCommandButton();
public slots:
void sendCommand();
void setCommandButtonName(QString text);
void startEditMode();
void endEditMode();
void writeSettings(QSettings& settings);
void readSettings(const QSettings& settings);
private:
Ui::QGCCommandButton *ui;
UASInterface* uas;
};
#endif // QGCCOMMANDBUTTON_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCCommandButton</class>
<widget class="QWidget" name="QGCCommandButton">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>882</width>
<height>430</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="100,0,0,0">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<item row="7" column="0" colspan="3">
<widget class="QComboBox" name="editCommandComboBox"/>
</item>
<item row="7" column="3">
<widget class="QPushButton" name="editFinishButton">
<property name="text">
<string>Done</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLineEdit" name="editButtonName">
<property name="text">
<string>&lt;Button Label&gt;</string>
</property>
</widget>
</item>
<item row="2" column="0" colspan="3">
<widget class="QLineEdit" name="editNameLabel">
<property name="text">
<string>&lt;Button Description Label (in front of button)&gt;</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QPushButton" name="commandButton">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Unnamed</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QSpinBox" name="editComponentSpinBox">
<property name="prefix">
<string>Component ID: </string>
</property>
<property name="minimum">
<number>0</number>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="6" column="2" colspan="2">
<widget class="QCheckBox" name="editConfirmationCheckBox">
<property name="toolTip">
<string>Set the confirm flag for this button. Some commands require that first one command is sent without confirm flag and then a second, equal command with confirm flag. This ensures safety.</string>
</property>
<property name="text">
<string>Set CONFIRM flag</string>
</property>
</widget>
</item>
<item row="3" column="0" colspan="4">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QDoubleSpinBox" name="editParam1SpinBox">
<property name="toolTip">
<string>PARAM1 Value as defined in MAV_CMD list</string>
</property>
<property name="statusTip">
<string>PARAM1 Value as defined in MAV_CMD list</string>
</property>
<property name="prefix">
<string>P1 </string>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="editParam2SpinBox">
<property name="toolTip">
<string>PARAM2 Value as defined in MAV_CMD list</string>
</property>
<property name="statusTip">
<string>PARAM2 Value as defined in MAV_CMD list</string>
</property>
<property name="prefix">
<string>P2: </string>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="editParam3SpinBox">
<property name="toolTip">
<string>PARAM3 Value as defined in MAV_CMD list</string>
</property>
<property name="statusTip">
<string>PARAM3 Value as defined in MAV_CMD list</string>
</property>
<property name="prefix">
<string>P3: </string>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="editParam4SpinBox">
<property name="toolTip">
<string>PARAM4 Value as defined in MAV_CMD list</string>
</property>
<property name="statusTip">
<string>PARAM4 Value as defined in MAV_CMD list</string>
</property>
<property name="prefix">
<string>P4: </string>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item row="4" column="0" colspan="3">
<widget class="QLabel" name="nameLabel">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Description</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QCheckBox" name="editParamsVisibleCheckBox">
<property name="text">
<string>Keep parameters visible</string>
</property>
</widget>
</item>
<item row="1" column="0" colspan="4">
<widget class="Line" name="editLine1">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="8" column="0" colspan="4">
<widget class="Line" name="editLine2">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections>
<connection>
<sender>editNameLabel</sender>
<signal>textChanged(QString)</signal>
<receiver>nameLabel</receiver>
<slot>setText(QString)</slot>
<hints>
<hint type="sourcelabel">
<x>114</x>
<y>22</y>
</hint>
<hint type="destinationlabel">
<x>114</x>
<y>55</y>
</hint>
</hints>
</connection>
</connections>
</ui>
......@@ -26,16 +26,19 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
scaledInt = ui->valueSlider->maximum() - ui->valueSlider->minimum();
ui->editDoneButton->hide();
ui->editMaxLabel->hide();
ui->editMinLabel->hide();
ui->editNameLabel->hide();
ui->editInstructionsLabel->hide();
ui->editRefreshParamsButton->hide();
ui->editSelectParamComboBox->hide();
ui->editSelectComponentComboBox->hide();
ui->editStatusLabel->hide();
ui->editMinSpinBox->hide();
ui->editMaxSpinBox->hide();
ui->editLine1->hide();
ui->editLine2->hide();
ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
// Sending actions
......@@ -112,11 +115,14 @@ void QGCParamSlider::selectParameter(int paramIndex)
void QGCParamSlider::startEditMode()
{
ui->valueSlider->hide();
ui->valueSpinBox->hide();
ui->nameLabel->hide();
ui->writeButton->hide();
ui->readButton->hide();
ui->editDoneButton->show();
ui->editMaxLabel->show();
ui->editMinLabel->show();
ui->editNameLabel->show();
ui->editInstructionsLabel->show();
ui->editRefreshParamsButton->show();
ui->editSelectParamComboBox->show();
ui->editSelectComponentComboBox->show();
......@@ -125,6 +131,8 @@ void QGCParamSlider::startEditMode()
ui->editMaxSpinBox->show();
ui->writeButton->hide();
ui->readButton->hide();
ui->editLine1->show();
ui->editLine2->show();
isInEditMode = true;
}
......@@ -141,18 +149,20 @@ void QGCParamSlider::endEditMode()
parameterMax = ui->editMaxSpinBox->value();
ui->editDoneButton->hide();
ui->editMaxLabel->hide();
ui->editMinLabel->hide();
ui->editNameLabel->hide();
ui->editInstructionsLabel->hide();
ui->editRefreshParamsButton->hide();
ui->editSelectParamComboBox->hide();
ui->editSelectComponentComboBox->hide();
ui->editStatusLabel->hide();
ui->editMinSpinBox->hide();
ui->editMaxSpinBox->hide();
ui->editLine1->hide();
ui->editLine2->hide();
ui->writeButton->show();
ui->readButton->show();
ui->valueSlider->show();
ui->valueSpinBox->show();
ui->nameLabel->show();
isInEditMode = false;
emit editingFinished();
}
......
......@@ -6,43 +6,47 @@
<rect>
<x>0</x>
<y>0</y>
<width>839</width>
<height>179</height>
<width>789</width>
<height>155</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="100,0,0,0,0,0,0,0,0">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="horizontalSpacing">
<number>6</number>
</property>
<property name="verticalSpacing">
<number>12</number>
</property>
<item row="1" column="1" colspan="3">
<item row="1" column="1" colspan="5">
<widget class="QLineEdit" name="editNameLabel">
<property name="text">
<string>Informal Name..</string>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="editMinLabel">
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QLabel" name="editMaxLabel">
<property name="text">
<string>Max</string>
<string>&lt;Parameter Name / Label&gt;</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="nameLabel">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Name</string>
</property>
......@@ -51,18 +55,14 @@
</property>
</widget>
</item>
<item row="2" column="3" colspan="2">
<widget class="QDoubleSpinBox" name="editMinSpinBox">
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item>
<item row="2" column="5">
<item row="2" column="5" colspan="2">
<widget class="QSlider" name="valueSlider">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
......@@ -77,23 +77,6 @@
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QDoubleSpinBox" name="editMaxSpinBox">
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item>
<item row="0" column="1" colspan="6">
<widget class="QLabel" name="editInstructionsLabel">
<property name="text">
<string>Please configure the parameter slider now:</string>
</property>
</widget>
</item>
<item row="5" column="1" colspan="6">
<widget class="QLabel" name="editStatusLabel">
<property name="text">
......@@ -101,7 +84,7 @@
</property>
</widget>
</item>
<item row="3" column="1" colspan="2">
<item row="3" column="1" colspan="3">
<widget class="QComboBox" name="editSelectComponentComboBox">
<property name="enabled">
<bool>false</bool>
......@@ -146,7 +129,7 @@
</property>
</widget>
</item>
<item row="3" column="7" colspan="2">
<item row="3" column="8">
<widget class="QPushButton" name="editRefreshParamsButton">
<property name="enabled">
<bool>true</bool>
......@@ -156,7 +139,7 @@
</property>
</widget>
</item>
<item row="5" column="7" colspan="2">
<item row="5" column="8">
<widget class="QPushButton" name="editDoneButton">
<property name="text">
<string>Done</string>
......@@ -180,7 +163,7 @@
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<width>0</width>
<height>20</height>
</size>
</property>
......@@ -207,18 +190,64 @@
<string>Transmit the current slider value to the system</string>
</property>
<property name="text">
<string/>
<string>W</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="9">
<widget class="Line" name="editLine1">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="icon">
<iconset resource="../../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="6" column="0" colspan="9">
<widget class="Line" name="editLine2">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QDoubleSpinBox" name="editMinSpinBox">
<property name="prefix">
<string>MIN: </string>
</property>
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item>
<item row="1" column="7" colspan="2">
<widget class="QDoubleSpinBox" name="editMaxSpinBox">
<property name="prefix">
<string>MAX: </string>
</property>
<property name="minimum">
<double>-999999999.000000000000000</double>
</property>
<property name="maximum">
<double>999999999.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources>
<include location="../../../mavground.qrc"/>
</resources>
<resources/>
<connections/>
</ui>
......@@ -10,6 +10,7 @@
#include "QGCParamSlider.h"
#include "QGCActionButton.h"
#include "QGCCommandButton.h"
#include "UASManager.h"
QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent) :
......@@ -106,6 +107,11 @@ QList<QGCToolWidget*> QGCToolWidget::createWidgetsFromSettings(QWidget* parent)
item = new QGCActionButton(newWidgets.at(i));
qDebug() << "CREATED BUTTON";
}
else if (type == "COMMANDBUTTON")
{
item = new QGCCommandButton(newWidgets.at(i));
qDebug() << "CREATED COMMANDBUTTON";
}
else if (type == "SLIDER")
{
item = new QGCParamSlider(newWidgets.at(i));
......@@ -182,9 +188,11 @@ void QGCToolWidget::contextMenuEvent (QContextMenuEvent* event)
{
QMenu menu(this);
menu.addAction(addParamAction);
menu.addAction(addButtonAction);
menu.addAction(addCommandAction);
menu.addAction(setTitleAction);
menu.addAction(deleteAction);
menu.addSeparator();
menu.addAction(addButtonAction);
menu.exec(event->globalPos());
}
......@@ -194,9 +202,9 @@ void QGCToolWidget::createActions()
addParamAction->setStatusTip(tr("Add a parameter setting slider widget to the tool"));
connect(addParamAction, SIGNAL(triggered()), this, SLOT(addParam()));
addButtonAction = new QAction(tr("New MAV &Command Button"), this);
addButtonAction->setStatusTip(tr("Add a new action button to the tool"));
connect(addButtonAction, SIGNAL(triggered()), this, SLOT(addAction()));
addCommandAction = new QAction(tr("New MAV &Command Button"), this);
addCommandAction->setStatusTip(tr("Add a new action button to the tool"));
connect(addCommandAction, SIGNAL(triggered()), this, SLOT(addCommand()));
setTitleAction = new QAction(tr("Set Widget Title"), this);
setTitleAction->setStatusTip(tr("Set the title caption of this tool widget"));
......@@ -213,6 +221,10 @@ void QGCToolWidget::createActions()
importAction = new QAction(tr("Import widget"), this);
importAction->setStatusTip(tr("Import this widget from a file (current content will be removed)"));
connect(exportAction, SIGNAL(triggered()), this, SLOT(importWidget()));
addButtonAction = new QAction(tr("New MAV Action Button (Deprecated)"), this);
addButtonAction->setStatusTip(tr("Add a new action button to the tool"));
connect(addButtonAction, SIGNAL(triggered()), this, SLOT(addAction()));
}
QMap<QString, QGCToolWidget*>* QGCToolWidget::instances()
......@@ -253,6 +265,18 @@ void QGCToolWidget::addAction()
button->startEditMode();
}
void QGCToolWidget::addCommand()
{
QGCCommandButton* button = new QGCCommandButton(this);
if (ui->hintLabel)
{
ui->hintLabel->deleteLater();
ui->hintLabel = NULL;
}
toolLayout->addWidget(button);
button->startEditMode();
}
void QGCToolWidget::addToolWidget(QGCToolWidgetItem* widget)
{
if (ui->hintLabel)
......
......@@ -45,6 +45,7 @@ signals:
protected:
QAction* addParamAction;
QAction* addButtonAction;
QAction* addCommandAction;
QAction* setTitleAction;
QAction* deleteAction;
QAction* exportAction;
......@@ -62,7 +63,9 @@ protected:
protected slots:
void addParam();
/** @deprecated */
void addAction();
void addCommand();
void setTitle();
......
......@@ -15,8 +15,20 @@
</property>
<layout class="QVBoxLayout" name="toolLayout">
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="hintLabel">
<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);
......
......@@ -6,14 +6,14 @@
<rect>
<x>0</x>
<y>0</y>
<width>1105</width>
<width>1228</width>
<height>25</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,10,10,10,10,10,0,0">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,0,10,10,10,10,0,0">
<property name="spacing">
<number>5</number>
</property>
......
Subproject commit 3eece4f7936d935256ec4ac6cf3ae726e5ddd7f1
Subproject commit 49db98933d97766016c18b4dadd6e238eec6c8f7
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