mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Moved framework to its own plugin
This commit is contained in:
parent
32ebdb63a3
commit
6d6111b9ac
@ -10,5 +10,6 @@
|
|||||||
<dependency name="UAVTalk" version="1.0.0"/>
|
<dependency name="UAVTalk" version="1.0.0"/>
|
||||||
<dependency name="UAVObjectUtil" version="1.0.0"/>
|
<dependency name="UAVObjectUtil" version="1.0.0"/>
|
||||||
<dependency name="UAVSettingsImportExport" version="1.0.0"/>
|
<dependency name="UAVSettingsImportExport" version="1.0.0"/>
|
||||||
|
<dependency name="UAVObjectWidgetUtils" version="1.0.0"/>
|
||||||
</dependencyList>
|
</dependencyList>
|
||||||
</plugin>
|
</plugin>
|
||||||
|
7
ground/openpilotgcs/src/plugins/config/config.pri
Normal file
7
ground/openpilotgcs/src/plugins/config/config.pri
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
#include(config_dependencies.pri)
|
||||||
|
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
|
||||||
|
include(../../plugins/uavtalk/uavtalk.pri)
|
||||||
|
# Add the include path to the built-in uavobject include files.
|
||||||
|
INCLUDEPATH += $$PWD
|
||||||
|
|
||||||
|
LIBS *= -l$$qtLibraryName(Config)
|
@ -1,13 +1,8 @@
|
|||||||
TEMPLATE = lib
|
TEMPLATE = lib
|
||||||
TARGET = Config
|
TARGET = Config
|
||||||
|
DEFINES += CONFIG_LIBRARY
|
||||||
QT += svg
|
QT += svg
|
||||||
include(../../openpilotgcsplugin.pri)
|
include(config_dependencies.pri)
|
||||||
include(../../libs/utils/utils.pri)
|
|
||||||
include(../../plugins/uavtalk/uavtalk.pri)
|
|
||||||
include(../../plugins/coreplugin/coreplugin.pri)
|
|
||||||
include(../../plugins/uavobjects/uavobjects.pri)
|
|
||||||
include(../../plugins/uavobjectutil/uavobjectutil.pri)
|
|
||||||
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
|
|
||||||
INCLUDEPATH += ../../libs/eigen
|
INCLUDEPATH += ../../libs/eigen
|
||||||
OTHER_FILES += Config.pluginspec
|
OTHER_FILES += Config.pluginspec
|
||||||
HEADERS += configplugin.h \
|
HEADERS += configplugin.h \
|
||||||
@ -19,25 +14,21 @@ HEADERS += configplugin.h \
|
|||||||
fancytabwidget.h \
|
fancytabwidget.h \
|
||||||
configinputwidget.h \
|
configinputwidget.h \
|
||||||
configoutputwidget.h \
|
configoutputwidget.h \
|
||||||
configtaskwidget.h \
|
|
||||||
configairframewidget.h \
|
configairframewidget.h \
|
||||||
config_pro_hw_widget.h \
|
config_pro_hw_widget.h \
|
||||||
config_cc_hw_widget.h \
|
config_cc_hw_widget.h \
|
||||||
configahrswidget.h \
|
configahrswidget.h \
|
||||||
configccattitudewidget.h \
|
configccattitudewidget.h \
|
||||||
mixercurvewidget.h \
|
|
||||||
mixercurvepoint.h \
|
|
||||||
mixercurveline.h \
|
|
||||||
configccpmwidget.h \
|
configccpmwidget.h \
|
||||||
configstabilizationwidget.h \
|
configstabilizationwidget.h \
|
||||||
assertions.h \
|
assertions.h \
|
||||||
calibration.h \
|
calibration.h \
|
||||||
defaultattitudewidget.h \
|
defaultattitudewidget.h \
|
||||||
smartsavebutton.h \
|
|
||||||
defaulthwsettingswidget.h \
|
defaulthwsettingswidget.h \
|
||||||
inputchannelform.h \
|
inputchannelform.h \
|
||||||
configcamerastabilizationwidget.h \
|
configcamerastabilizationwidget.h \
|
||||||
outputchannelform.h
|
outputchannelform.h \
|
||||||
|
config_global.h
|
||||||
SOURCES += configplugin.cpp \
|
SOURCES += configplugin.cpp \
|
||||||
configgadgetconfiguration.cpp \
|
configgadgetconfiguration.cpp \
|
||||||
configgadgetwidget.cpp \
|
configgadgetwidget.cpp \
|
||||||
@ -45,7 +36,6 @@ SOURCES += configplugin.cpp \
|
|||||||
configgadgetoptionspage.cpp \
|
configgadgetoptionspage.cpp \
|
||||||
configgadget.cpp \
|
configgadget.cpp \
|
||||||
fancytabwidget.cpp \
|
fancytabwidget.cpp \
|
||||||
configtaskwidget.cpp \
|
|
||||||
configinputwidget.cpp \
|
configinputwidget.cpp \
|
||||||
configoutputwidget.cpp \
|
configoutputwidget.cpp \
|
||||||
configairframewidget.cpp \
|
configairframewidget.cpp \
|
||||||
@ -53,9 +43,6 @@ SOURCES += configplugin.cpp \
|
|||||||
config_cc_hw_widget.cpp \
|
config_cc_hw_widget.cpp \
|
||||||
configahrswidget.cpp \
|
configahrswidget.cpp \
|
||||||
configccattitudewidget.cpp \
|
configccattitudewidget.cpp \
|
||||||
mixercurvewidget.cpp \
|
|
||||||
mixercurvepoint.cpp \
|
|
||||||
mixercurveline.cpp \
|
|
||||||
configccpmwidget.cpp \
|
configccpmwidget.cpp \
|
||||||
configstabilizationwidget.cpp \
|
configstabilizationwidget.cpp \
|
||||||
twostep.cpp \
|
twostep.cpp \
|
||||||
@ -63,7 +50,6 @@ SOURCES += configplugin.cpp \
|
|||||||
gyro-calibration.cpp \
|
gyro-calibration.cpp \
|
||||||
alignment-calibration.cpp \
|
alignment-calibration.cpp \
|
||||||
defaultattitudewidget.cpp \
|
defaultattitudewidget.cpp \
|
||||||
smartsavebutton.cpp \
|
|
||||||
defaulthwsettingswidget.cpp \
|
defaulthwsettingswidget.cpp \
|
||||||
inputchannelform.cpp \
|
inputchannelform.cpp \
|
||||||
configcamerastabilizationwidget.cpp \
|
configcamerastabilizationwidget.cpp \
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGCCHWWIDGET_H
|
#define CONFIGCCHWWIDGET_H
|
||||||
|
|
||||||
#include "ui_cc_hw_settings.h"
|
#include "ui_cc_hw_settings.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -0,0 +1,8 @@
|
|||||||
|
include(../../openpilotgcsplugin.pri)
|
||||||
|
include(../../libs/utils/utils.pri)
|
||||||
|
include(../../plugins/uavtalk/uavtalk.pri)
|
||||||
|
include(../../plugins/coreplugin/coreplugin.pri)
|
||||||
|
include(../../plugins/uavobjects/uavobjects.pri)
|
||||||
|
include(../../plugins/uavobjectutil/uavobjectutil.pri)
|
||||||
|
include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri)
|
||||||
|
include(../../plugins/uavobjectwidgetutils/uavobjectwidgetutils.pri)
|
41
ground/openpilotgcs/src/plugins/config/config_global.h
Normal file
41
ground/openpilotgcs/src/plugins/config/config_global.h
Normal file
@ -0,0 +1,41 @@
|
|||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
*
|
||||||
|
* @file config_global.h
|
||||||
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
|
* @see The GNU Public License (GPL) Version 3
|
||||||
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
|
* @{
|
||||||
|
* @addtogroup Congig Plugin
|
||||||
|
* @{
|
||||||
|
* @brief The Congig GCS plugin
|
||||||
|
*****************************************************************************/
|
||||||
|
/*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
|
* for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License along
|
||||||
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CONFIG_GLOBAL_H
|
||||||
|
#define CONFIG_GLOBAL_H
|
||||||
|
|
||||||
|
#include <QtCore/qglobal.h>
|
||||||
|
|
||||||
|
#if defined(CONFIG_LIBRARY)
|
||||||
|
# define CONFIG_EXPORT Q_DECL_EXPORT
|
||||||
|
#else
|
||||||
|
# define CONFIG_EXPORT Q_DECL_IMPORT
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#endif // CONFIG_GLOBAL_H
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGPROHWWIDGET_H
|
#define CONFIGPROHWWIDGET_H
|
||||||
|
|
||||||
#include "ui_pro_hw_settings.h"
|
#include "ui_pro_hw_settings.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -30,7 +30,7 @@
|
|||||||
#include <Eigen/StdVector>
|
#include <Eigen/StdVector>
|
||||||
|
|
||||||
#include "ui_ahrs.h"
|
#include "ui_ahrs.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGAIRFRAMEWIDGET_H
|
#define CONFIGAIRFRAMEWIDGET_H
|
||||||
|
|
||||||
#include "ui_airframe.h"
|
#include "ui_airframe.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGCAMERASTABILIZATIONWIDGET_H
|
#define CONFIGCAMERASTABILIZATIONWIDGET_H
|
||||||
|
|
||||||
#include "ui_camerastabilization.h"
|
#include "ui_camerastabilization.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CCATTITUDEWIDGET_H
|
#define CCATTITUDEWIDGET_H
|
||||||
|
|
||||||
#include "ui_ccattitude.h"
|
#include "ui_ccattitude.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGccpmWIDGET_H
|
#define CONFIGccpmWIDGET_H
|
||||||
|
|
||||||
#include "ui_ccpm.h"
|
#include "ui_ccpm.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGGADGET_H
|
#define CONFIGGADGET_H
|
||||||
|
|
||||||
#include <coreplugin/iuavgadget.h>
|
#include <coreplugin/iuavgadget.h>
|
||||||
#include "configgadgetwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
|
|
||||||
class IUAVGadget;
|
class IUAVGadget;
|
||||||
//class QList<int>;
|
//class QList<int>;
|
||||||
@ -46,7 +46,7 @@ public:
|
|||||||
ConfigGadget(QString classId, ConfigGadgetWidget *widget, QWidget *parent = 0);
|
ConfigGadget(QString classId, ConfigGadgetWidget *widget, QWidget *parent = 0);
|
||||||
~ConfigGadget();
|
~ConfigGadget();
|
||||||
|
|
||||||
QWidget *widget() { return m_widget; }
|
QWidget *widget() { return (QWidget*)m_widget; }
|
||||||
void loadConfiguration(IUAVGadgetConfiguration* config);
|
void loadConfiguration(IUAVGadgetConfiguration* config);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -40,7 +40,7 @@
|
|||||||
#include <QMessageBox>
|
#include <QMessageBox>
|
||||||
//#include "fancytabwidget.h"
|
//#include "fancytabwidget.h"
|
||||||
#include "utils/mytabbedstackwidget.h"
|
#include "utils/mytabbedstackwidget.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
|
|
||||||
class ConfigGadgetWidget: public QWidget
|
class ConfigGadgetWidget: public QWidget
|
||||||
{
|
{
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGINPUTWIDGET_H
|
#define CONFIGINPUTWIDGET_H
|
||||||
|
|
||||||
#include "ui_input.h"
|
#include "ui_input.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGOUTPUTWIDGET_H
|
#define CONFIGOUTPUTWIDGET_H
|
||||||
|
|
||||||
#include "ui_output.h"
|
#include "ui_output.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define CONFIGSTABILIZATIONWIDGET_H
|
#define CONFIGSTABILIZATIONWIDGET_H
|
||||||
|
|
||||||
#include "ui_stabilization.h"
|
#include "ui_stabilization.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define DEFAULTATTITUDEWIDGET_H
|
#define DEFAULTATTITUDEWIDGET_H
|
||||||
|
|
||||||
#include "ui_defaultattitude.h"
|
#include "ui_defaultattitude.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -28,7 +28,7 @@
|
|||||||
#define DEFAULTHWSETTINGSt_H
|
#define DEFAULTHWSETTINGSt_H
|
||||||
|
|
||||||
#include "ui_defaulthwsettings.h"
|
#include "ui_defaulthwsettings.h"
|
||||||
#include "configtaskwidget.h"
|
#include "../uavobjectwidgetutils/configtaskwidget.h"
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
|
@ -51,7 +51,7 @@ public:
|
|||||||
QString contextHelpId() const { return QString(); }
|
QString contextHelpId() const { return QString(); }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
QWidget *m_widget;
|
QWidget *m_widget;
|
||||||
QList<int> m_context;
|
QList<int> m_context;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -3,7 +3,6 @@ TARGET = DebugGadget
|
|||||||
|
|
||||||
include(../../openpilotgcsplugin.pri)
|
include(../../openpilotgcsplugin.pri)
|
||||||
include(../../plugins/coreplugin/coreplugin.pri)
|
include(../../plugins/coreplugin/coreplugin.pri)
|
||||||
include(../../libs/libqxt/core/logengines.pri)
|
|
||||||
HEADERS += debugplugin.h \
|
HEADERS += debugplugin.h \
|
||||||
debugengine.h
|
debugengine.h
|
||||||
HEADERS += debuggadget.h
|
HEADERS += debuggadget.h
|
||||||
|
@ -112,6 +112,7 @@ SUBDIRS += plugin_systemhealth
|
|||||||
plugin_config.subdir = config
|
plugin_config.subdir = config
|
||||||
plugin_config.depends = plugin_coreplugin
|
plugin_config.depends = plugin_coreplugin
|
||||||
plugin_config.depends += plugin_uavobjects
|
plugin_config.depends += plugin_uavobjects
|
||||||
|
plugin_config.depends += plugin_uavobjectwidgetutils
|
||||||
plugin_config.depends += plugin_uavsettingsimportexport
|
plugin_config.depends += plugin_uavsettingsimportexport
|
||||||
SUBDIRS += plugin_config
|
SUBDIRS += plugin_config
|
||||||
|
|
||||||
@ -183,6 +184,12 @@ plugin_uavobjectutil.depends = plugin_coreplugin
|
|||||||
plugin_uavobjectutil.depends += plugin_uavobjects
|
plugin_uavobjectutil.depends += plugin_uavobjects
|
||||||
SUBDIRS += plugin_uavobjectutil
|
SUBDIRS += plugin_uavobjectutil
|
||||||
|
|
||||||
|
# UAV Object Widget Utility plugin
|
||||||
|
plugin_uavobjectwidgetutils.subdir = uavobjectwidgetutils
|
||||||
|
plugin_uavobjectwidgetutils.depends = plugin_coreplugin
|
||||||
|
plugin_uavobjectwidgetutils.depends += plugin_uavobjects
|
||||||
|
SUBDIRS += plugin_uavobjectwidgetutils
|
||||||
|
|
||||||
# Magic Waypoint gadget
|
# Magic Waypoint gadget
|
||||||
plugin_magicwaypoint.subdir = magicwaypoint
|
plugin_magicwaypoint.subdir = magicwaypoint
|
||||||
plugin_magicwaypoint.depends = plugin_coreplugin
|
plugin_magicwaypoint.depends = plugin_coreplugin
|
||||||
|
@ -6,6 +6,6 @@
|
|||||||
<url>http://www.openpilot.org</url>
|
<url>http://www.openpilot.org</url>
|
||||||
<dependencyList>
|
<dependencyList>
|
||||||
<dependency name="Core" version="1.0.0"/>
|
<dependency name="Core" version="1.0.0"/>
|
||||||
<dependency name="UAVObjects" version="1.0.0"/>
|
<dependency name="UAVObjects" version="1.0.0"/>
|
||||||
</dependencyList>
|
</dependencyList>
|
||||||
</plugin>
|
</plugin>
|
||||||
|
@ -0,0 +1,13 @@
|
|||||||
|
<plugin name="UAVObjectWidgetUtils" version="1.0.0" compatVersion="1.0.0">
|
||||||
|
<vendor>The OpenPilot Project</vendor>
|
||||||
|
<copyright>(C) 2010 OpenPilot Project</copyright>
|
||||||
|
<license>The GNU Public License (GPL) Version 3</license>
|
||||||
|
<description>Utils classes for UAVObjects to Widget relations</description>
|
||||||
|
<url>http://www.openpilot.org</url>
|
||||||
|
<dependencyList>
|
||||||
|
<dependency name="Core" version="1.0.0"/>
|
||||||
|
<dependency name="UAVObjects" version="1.0.0"/>
|
||||||
|
<dependency name="UAVObjectUtil" version="1.0.0"/>
|
||||||
|
<dependency name="UAVSettingsImportExport" version="1.0.0"/>
|
||||||
|
</dependencyList>
|
||||||
|
</plugin>
|
@ -1,862 +1,865 @@
|
|||||||
/**
|
/**
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*
|
*
|
||||||
* @file configtaskwidget.cpp
|
* @file configtaskwidget.cpp
|
||||||
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
* @addtogroup GCSPlugins GCS Plugins
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
* @{
|
* @{
|
||||||
* @addtogroup ConfigPlugin Config Plugin
|
* @addtogroup ConfigPlugin Config Plugin
|
||||||
* @{
|
* @{
|
||||||
* @brief The Configuration Gadget used to update settings in the firmware
|
* @brief The Configuration Gadget used to update settings in the firmware
|
||||||
*****************************************************************************/
|
*****************************************************************************/
|
||||||
/*
|
/*
|
||||||
* This program is free software; you can redistribute it and/or modify
|
* This program is free software; you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation; either version 3 of the License, or
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This program is distributed in the hope that it will be useful, but
|
* This program is distributed in the hope that it will be useful, but
|
||||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
* for more details.
|
* for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License along
|
* You should have received a copy of the GNU General Public License along
|
||||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
#include "configtaskwidget.h"
|
#include "configtaskwidget.h"
|
||||||
#include <QtGui/QWidget>
|
#include <QtGui/QWidget>
|
||||||
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
|
||||||
#include "configgadgetwidget.h"
|
|
||||||
|
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);")
|
||||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);")
|
{
|
||||||
{
|
pm = ExtensionSystem::PluginManager::instance();
|
||||||
pm = ExtensionSystem::PluginManager::instance();
|
objManager = pm->getObject<UAVObjectManager>();
|
||||||
objManager = pm->getObject<UAVObjectManager>();
|
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
|
||||||
connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
|
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
|
||||||
connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
|
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
|
||||||
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
|
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
|
||||||
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects()));
|
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects()));
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addWidget(QWidget * widget)
|
void ConfigTaskWidget::addWidget(QWidget * widget)
|
||||||
{
|
{
|
||||||
addUAVObjectToWidgetRelation("","",widget);
|
addUAVObjectToWidgetRelation("","",widget);
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addUAVObject(QString objectName)
|
void ConfigTaskWidget::addUAVObject(QString objectName)
|
||||||
{
|
{
|
||||||
addUAVObjectToWidgetRelation(objectName,"",NULL);
|
addUAVObjectToWidgetRelation(objectName,"",NULL);
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index)
|
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index)
|
||||||
{
|
{
|
||||||
UAVObject *obj=NULL;
|
UAVObject *obj=NULL;
|
||||||
UAVObjectField *_field=NULL;
|
UAVObjectField *_field=NULL;
|
||||||
obj = objManager->getObject(QString(object));
|
obj = objManager->getObject(QString(object));
|
||||||
Q_ASSERT(obj);
|
Q_ASSERT(obj);
|
||||||
_field = obj->getField(QString(field));
|
_field = obj->getField(QString(field));
|
||||||
Q_ASSERT(_field);
|
Q_ASSERT(_field);
|
||||||
addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index));
|
addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index));
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, float scale, bool isLimited, QList<int> *defaultReloadGroups)
|
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, float scale, bool isLimited, QList<int> *defaultReloadGroups)
|
||||||
{
|
{
|
||||||
UAVObject *obj=objManager->getObject(QString(object));
|
UAVObject *obj=objManager->getObject(QString(object));
|
||||||
Q_ASSERT(obj);
|
Q_ASSERT(obj);
|
||||||
UAVObjectField *_field;
|
UAVObjectField *_field;
|
||||||
if(!field.isEmpty() && obj)
|
if(!field.isEmpty() && obj)
|
||||||
_field = obj->getField(QString(field));
|
_field = obj->getField(QString(field));
|
||||||
int index=_field->getElementNames().indexOf(QString(element));
|
int index=_field->getElementNames().indexOf(QString(element));
|
||||||
addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups);
|
addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups);
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,float scale,bool isLimited,QList<int>* defaultReloadGroups)
|
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,float scale,bool isLimited,QList<int>* defaultReloadGroups)
|
||||||
{
|
{
|
||||||
if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups))
|
if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups))
|
||||||
return;
|
return;
|
||||||
|
|
||||||
UAVObject *obj=NULL;
|
UAVObject *obj=NULL;
|
||||||
UAVObjectField *_field=NULL;
|
UAVObjectField *_field=NULL;
|
||||||
if(!object.isEmpty())
|
if(!object.isEmpty())
|
||||||
{
|
{
|
||||||
obj = objManager->getObject(QString(object));
|
obj = objManager->getObject(QString(object));
|
||||||
Q_ASSERT(obj);
|
Q_ASSERT(obj);
|
||||||
objectUpdates.insert(obj,true);
|
objectUpdates.insert(obj,true);
|
||||||
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*)));
|
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*)));
|
||||||
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
}
|
}
|
||||||
if(!field.isEmpty() && obj)
|
if(!field.isEmpty() && obj)
|
||||||
_field = obj->getField(QString(field));
|
_field = obj->getField(QString(field));
|
||||||
objectToWidget * ow=new objectToWidget();
|
objectToWidget * ow=new objectToWidget();
|
||||||
ow->field=_field;
|
ow->field=_field;
|
||||||
ow->object=obj;
|
ow->object=obj;
|
||||||
ow->widget=widget;
|
ow->widget=widget;
|
||||||
ow->index=index;
|
ow->index=index;
|
||||||
ow->scale=scale;
|
ow->scale=scale;
|
||||||
ow->isLimited=isLimited;
|
ow->isLimited=isLimited;
|
||||||
objOfInterest.append(ow);
|
objOfInterest.append(ow);
|
||||||
if(obj)
|
if(obj)
|
||||||
{
|
{
|
||||||
if(smartsave)
|
if(smartsave)
|
||||||
{
|
{
|
||||||
smartsave->addObject((UAVDataObject*)obj);
|
smartsave->addObject((UAVDataObject*)obj);
|
||||||
emit objectAdded(obj);
|
emit objectAdded(obj);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(widget==NULL)
|
if(widget==NULL)
|
||||||
{
|
{
|
||||||
// do nothing
|
// do nothing
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged()));
|
connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged()));
|
||||||
if(defaultReloadGroups)
|
if(defaultReloadGroups)
|
||||||
addWidgetToDefaultReloadGroups(widget,defaultReloadGroups);
|
addWidgetToDefaultReloadGroups(widget,defaultReloadGroups);
|
||||||
shadowsList.insert(widget,ow);
|
shadowsList.insert(widget,ow);
|
||||||
loadWidgetLimits(widget,_field,index,isLimited,scale);
|
loadWidgetLimits(widget,_field,index,isLimited,scale);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
ConfigTaskWidget::~ConfigTaskWidget()
|
ConfigTaskWidget::~ConfigTaskWidget()
|
||||||
{
|
{
|
||||||
if(smartsave)
|
if(smartsave)
|
||||||
delete smartsave;
|
delete smartsave;
|
||||||
foreach(QList<objectToWidget*>* pointer,defaultReloadGroups.values())
|
foreach(QList<objectToWidget*>* pointer,defaultReloadGroups.values())
|
||||||
{
|
{
|
||||||
if(pointer)
|
if(pointer)
|
||||||
delete pointer;
|
delete pointer;
|
||||||
}
|
}
|
||||||
foreach (objectToWidget* oTw, objOfInterest)
|
foreach (objectToWidget* oTw, objOfInterest)
|
||||||
{
|
{
|
||||||
if(oTw)
|
if(oTw)
|
||||||
delete oTw;
|
delete oTw;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
|
void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
|
||||||
{
|
{
|
||||||
qDebug()<<"ConfigTaskWidget::saveObjectToSD";
|
qDebug()<<"ConfigTaskWidget::saveObjectToSD";
|
||||||
// saveObjectToSD is now handled by the UAVUtils plugin in one
|
// saveObjectToSD is now handled by the UAVUtils plugin in one
|
||||||
// central place (and one central queue)
|
// central place (and one central queue)
|
||||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||||
utilMngr->saveObjectToSD(obj);
|
utilMngr->saveObjectToSD(obj);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
UAVObjectManager* ConfigTaskWidget::getObjectManager() {
|
UAVObjectManager* ConfigTaskWidget::getObjectManager() {
|
||||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||||
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
|
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
|
||||||
Q_ASSERT(objMngr);
|
Q_ASSERT(objMngr);
|
||||||
return objMngr;
|
return objMngr;
|
||||||
}
|
}
|
||||||
|
|
||||||
double ConfigTaskWidget::listMean(QList<double> list)
|
double ConfigTaskWidget::listMean(QList<double> list)
|
||||||
{
|
{
|
||||||
double accum = 0;
|
double accum = 0;
|
||||||
for(int i = 0; i < list.size(); i++)
|
for(int i = 0; i < list.size(); i++)
|
||||||
accum += list[i];
|
accum += list[i];
|
||||||
return accum / list.size();
|
return accum / list.size();
|
||||||
}
|
}
|
||||||
|
|
||||||
// ************************************
|
// ************************************
|
||||||
// telemetry start/stop connect/disconnect signals
|
// telemetry start/stop connect/disconnect signals
|
||||||
|
|
||||||
void ConfigTaskWidget::onAutopilotDisconnect()
|
void ConfigTaskWidget::onAutopilotDisconnect()
|
||||||
{
|
{
|
||||||
isConnected=false;
|
isConnected=false;
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
invalidateObjects();
|
invalidateObjects();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::onAutopilotConnect()
|
void ConfigTaskWidget::onAutopilotConnect()
|
||||||
{
|
{
|
||||||
invalidateObjects();
|
invalidateObjects();
|
||||||
dirty=false;
|
dirty=false;
|
||||||
isConnected=true;
|
isConnected=true;
|
||||||
enableControls(true);
|
enableControls(true);
|
||||||
refreshWidgetsValues();
|
refreshWidgetsValues();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::populateWidgets()
|
void ConfigTaskWidget::populateWidgets()
|
||||||
{
|
{
|
||||||
bool dirtyBack=dirty;
|
bool dirtyBack=dirty;
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
|
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
|
||||||
{
|
{
|
||||||
// do nothing
|
// do nothing
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited);
|
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited);
|
||||||
}
|
}
|
||||||
setDirty(dirtyBack);
|
setDirty(dirtyBack);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::refreshWidgetsValues()
|
void ConfigTaskWidget::refreshWidgetsValues()
|
||||||
{
|
{
|
||||||
bool dirtyBack=dirty;
|
bool dirtyBack=dirty;
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
|
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
|
||||||
{
|
{
|
||||||
//do nothing
|
//do nothing
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited);
|
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale,ow->isLimited);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
setDirty(dirtyBack);
|
setDirty(dirtyBack);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::updateObjectsFromWidgets()
|
void ConfigTaskWidget::updateObjectsFromWidgets()
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(ow->object==NULL || ow->field==NULL)
|
if(ow->object==NULL || ow->field==NULL)
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
setFieldFromWidget(ow->widget,ow->field,ow->index,ow->scale);
|
setFieldFromWidget(ow->widget,ow->field,ow->index,ow->scale);
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
|
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
|
||||||
{
|
{
|
||||||
smartsave=new smartSaveButton(update,save);
|
smartsave=new smartSaveButton(update,save);
|
||||||
connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
||||||
connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty()));
|
connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty()));
|
||||||
connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates()));
|
connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates()));
|
||||||
connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates()));
|
connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates()));
|
||||||
if(objOfInterest.count()>0)
|
if(objOfInterest.count()>0)
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * oTw,objOfInterest)
|
foreach(objectToWidget * oTw,objOfInterest)
|
||||||
{
|
{
|
||||||
smartsave->addObject((UAVDataObject*)oTw->object);
|
smartsave->addObject((UAVDataObject*)oTw->object);
|
||||||
emit objectAdded(oTw->object);
|
emit objectAdded(oTw->object);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::enableControls(bool enable)
|
void ConfigTaskWidget::enableControls(bool enable)
|
||||||
{
|
{
|
||||||
if(smartsave)
|
if(smartsave)
|
||||||
smartsave->enableControls(enable);
|
smartsave->enableControls(enable);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::widgetsContentsChanged()
|
void ConfigTaskWidget::widgetsContentsChanged()
|
||||||
{
|
{
|
||||||
float scale;
|
float scale;
|
||||||
objectToWidget * oTw= shadowsList.value((QWidget*)sender(),NULL);
|
objectToWidget * oTw= shadowsList.value((QWidget*)sender(),NULL);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
qDebug()<<"sender:"<<(quint32)sender();
|
qDebug()<<"sender:"<<(quint32)sender();
|
||||||
foreach(QWidget * w,shadowsList.keys())
|
foreach(QWidget * w,shadowsList.keys())
|
||||||
qDebug()<<"in list:"<<(quint32)w;
|
qDebug()<<"in list:"<<(quint32)w;
|
||||||
if(oTw)
|
if(oTw)
|
||||||
qDebug()<<"in oTw OK"<<(quint32)oTw->widget;
|
qDebug()<<"in oTw OK"<<(quint32)oTw->widget;
|
||||||
*/
|
*/
|
||||||
if(oTw)
|
if(oTw)
|
||||||
{
|
{
|
||||||
if(oTw->widget==(QWidget*)sender())
|
if(oTw->widget==(QWidget*)sender())
|
||||||
{
|
{
|
||||||
scale=oTw->scale;
|
scale=oTw->scale;
|
||||||
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),oTw->scale),oTw->scale);
|
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),oTw->scale),oTw->scale);
|
||||||
qDebug()<<"sender was master";
|
qDebug()<<"sender was master";
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
foreach (shadow * sh, oTw->shadowsList)
|
foreach (shadow * sh, oTw->shadowsList)
|
||||||
{
|
{
|
||||||
if(sh->widget==(QWidget*)sender())
|
if(sh->widget==(QWidget*)sender())
|
||||||
{
|
{
|
||||||
scale=sh->scale;
|
scale=sh->scale;
|
||||||
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),scale);
|
checkWidgetsLimits((QWidget*)sender(),oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),scale);
|
||||||
qDebug()<<"sender was shadow";
|
qDebug()<<"sender was shadow";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(oTw->widget!=(QWidget *)sender())
|
if(oTw->widget!=(QWidget *)sender())
|
||||||
{
|
{
|
||||||
checkWidgetsLimits(oTw->widget,oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
checkWidgetsLimits(oTw->widget,oTw->field,oTw->index,oTw->isLimited,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
||||||
setWidgetFromVariant(oTw->widget,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
setWidgetFromVariant(oTw->widget,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
||||||
}
|
}
|
||||||
foreach (shadow * sh, oTw->shadowsList)
|
foreach (shadow * sh, oTw->shadowsList)
|
||||||
{
|
{
|
||||||
if(sh->widget!=(QWidget*)sender())
|
if(sh->widget!=(QWidget*)sender())
|
||||||
{
|
{
|
||||||
checkWidgetsLimits(sh->widget,oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
checkWidgetsLimits(sh->widget,oTw->field,oTw->index,sh->isLimited,getVariantFromWidget((QWidget*)sender(),scale),oTw->scale);
|
||||||
setWidgetFromVariant(sh->widget,getVariantFromWidget((QWidget*)sender(),scale),sh->scale);
|
setWidgetFromVariant(sh->widget,getVariantFromWidget((QWidget*)sender(),scale),sh->scale);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
setDirty(true);
|
setDirty(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::clearDirty()
|
void ConfigTaskWidget::clearDirty()
|
||||||
{
|
{
|
||||||
setDirty(false);
|
setDirty(false);
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::setDirty(bool value)
|
void ConfigTaskWidget::setDirty(bool value)
|
||||||
{
|
{
|
||||||
dirty=value;
|
dirty=value;
|
||||||
}
|
}
|
||||||
bool ConfigTaskWidget::isDirty()
|
bool ConfigTaskWidget::isDirty()
|
||||||
{
|
{
|
||||||
if(isConnected)
|
if(isConnected)
|
||||||
return dirty;
|
return dirty;
|
||||||
else
|
else
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::disableObjUpdates()
|
void ConfigTaskWidget::disableObjUpdates()
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * obj,objOfInterest)
|
foreach(objectToWidget * obj,objOfInterest)
|
||||||
{
|
{
|
||||||
if(obj->object)
|
if(obj->object)
|
||||||
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::enableObjUpdates()
|
void ConfigTaskWidget::enableObjUpdates()
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * obj,objOfInterest)
|
foreach(objectToWidget * obj,objOfInterest)
|
||||||
{
|
{
|
||||||
if(obj->object)
|
if(obj->object)
|
||||||
connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::objectUpdated(UAVObject *obj)
|
void ConfigTaskWidget::objectUpdated(UAVObject *obj)
|
||||||
{
|
{
|
||||||
objectUpdates[obj]=true;
|
objectUpdates[obj]=true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::removeObject(UAVObject * obj)
|
void ConfigTaskWidget::removeObject(UAVObject * obj)
|
||||||
{
|
{
|
||||||
emit objectRemoved(obj);
|
emit objectRemoved(obj);
|
||||||
QList<objectToWidget*> toRemove;
|
QList<objectToWidget*> toRemove;
|
||||||
foreach(objectToWidget * oTw,objOfInterest)
|
foreach(objectToWidget * oTw,objOfInterest)
|
||||||
{
|
{
|
||||||
if(oTw->object==obj)
|
if(oTw->object==obj)
|
||||||
{
|
{
|
||||||
toRemove.append(oTw);
|
toRemove.append(oTw);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
foreach(objectToWidget * oTw,toRemove)
|
foreach(objectToWidget * oTw,toRemove)
|
||||||
{
|
{
|
||||||
objOfInterest.removeAll(oTw);
|
objOfInterest.removeAll(oTw);
|
||||||
smartsave->removeObject((UAVDataObject*)oTw->object);
|
smartsave->removeObject((UAVDataObject*)oTw->object);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::removeAllObjects()
|
void ConfigTaskWidget::removeAllObjects()
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * oTw,objOfInterest)
|
foreach(objectToWidget * oTw,objOfInterest)
|
||||||
{
|
{
|
||||||
emit objectRemoved(oTw->object);
|
emit objectRemoved(oTw->object);
|
||||||
}
|
}
|
||||||
objOfInterest.clear();
|
objOfInterest.clear();
|
||||||
smartsave->removeAllObjects();
|
smartsave->removeAllObjects();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ConfigTaskWidget::allObjectsUpdated()
|
bool ConfigTaskWidget::allObjectsUpdated()
|
||||||
{
|
{
|
||||||
bool ret=true;
|
bool ret=true;
|
||||||
foreach(UAVObject *obj, objectUpdates.keys())
|
foreach(UAVObject *obj, objectUpdates.keys())
|
||||||
{
|
{
|
||||||
ret=ret & objectUpdates[obj];
|
ret=ret & objectUpdates[obj];
|
||||||
}
|
}
|
||||||
qDebug()<<"ALL OBJECTS UPDATE:"<<ret;
|
qDebug()<<"ALL OBJECTS UPDATE:"<<ret;
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::invalidateObjects()
|
void ConfigTaskWidget::invalidateObjects()
|
||||||
{
|
{
|
||||||
foreach(UAVObject *obj, objectUpdates.keys())
|
foreach(UAVObject *obj, objectUpdates.keys())
|
||||||
{
|
{
|
||||||
objectUpdates[obj]=false;
|
objectUpdates[obj]=false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, float scale, bool isLimited,QList<int>* defaultReloadGroups)
|
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, float scale, bool isLimited,QList<int>* defaultReloadGroups)
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * oTw,objOfInterest)
|
foreach(objectToWidget * oTw,objOfInterest)
|
||||||
{
|
{
|
||||||
if(!oTw->object || !oTw->widget)
|
if(!oTw->object || !oTw->widget)
|
||||||
continue;
|
continue;
|
||||||
if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index)
|
if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index)
|
||||||
{
|
{
|
||||||
shadow * sh=new shadow;
|
shadow * sh=new shadow;
|
||||||
sh->isLimited=isLimited;
|
sh->isLimited=isLimited;
|
||||||
sh->scale=scale;
|
sh->scale=scale;
|
||||||
sh->widget=widget;
|
sh->widget=widget;
|
||||||
oTw->shadowsList.append(sh);
|
oTw->shadowsList.append(sh);
|
||||||
shadowsList.insert(widget,oTw);
|
shadowsList.insert(widget,oTw);
|
||||||
connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged()));
|
connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged()));
|
||||||
if(defaultReloadGroups)
|
if(defaultReloadGroups)
|
||||||
addWidgetToDefaultReloadGroups(widget,defaultReloadGroups);
|
addWidgetToDefaultReloadGroups(widget,defaultReloadGroups);
|
||||||
return true;
|
loadWidgetLimits(widget,oTw->field,oTw->index,isLimited,scale);
|
||||||
}
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
}
|
||||||
}
|
return false;
|
||||||
|
}
|
||||||
void ConfigTaskWidget::autoLoadWidgets()
|
|
||||||
{
|
void ConfigTaskWidget::autoLoadWidgets()
|
||||||
QPushButton * saveButtonWidget=NULL;
|
{
|
||||||
QPushButton * applyButtonWidget=NULL;
|
QPushButton * saveButtonWidget=NULL;
|
||||||
foreach(QObject * widget,this->children())
|
QPushButton * applyButtonWidget=NULL;
|
||||||
{
|
foreach(QObject * widget,this->children())
|
||||||
QVariant info=widget->property("objrelation");
|
{
|
||||||
if(info.isValid())
|
QVariant info=widget->property("objrelation");
|
||||||
{
|
if(info.isValid())
|
||||||
uiRelationAutomation uiRelation;
|
{
|
||||||
uiRelation.buttonType=none;
|
uiRelationAutomation uiRelation;
|
||||||
foreach(QString str, info.toStringList())
|
uiRelation.buttonType=none;
|
||||||
{
|
foreach(QString str, info.toStringList())
|
||||||
QString prop=str.split(":").at(0);
|
{
|
||||||
QString value=str.split(":").at(1);
|
QString prop=str.split(":").at(0);
|
||||||
if(prop== "objname")
|
QString value=str.split(":").at(1);
|
||||||
uiRelation.objname=value;
|
if(prop== "objname")
|
||||||
else if(prop== "fieldname")
|
uiRelation.objname=value;
|
||||||
uiRelation.fieldname=value;
|
else if(prop== "fieldname")
|
||||||
else if(prop=="element")
|
uiRelation.fieldname=value;
|
||||||
uiRelation.element=value;
|
else if(prop=="element")
|
||||||
else if(prop== "scale")
|
uiRelation.element=value;
|
||||||
{
|
else if(prop== "scale")
|
||||||
if(value=="null")
|
{
|
||||||
uiRelation.scale=1;
|
if(value=="null")
|
||||||
else
|
uiRelation.scale=1;
|
||||||
uiRelation.scale=value.toFloat();
|
else
|
||||||
}
|
uiRelation.scale=value.toFloat();
|
||||||
else if(prop== "ismaster")
|
}
|
||||||
{
|
else if(prop== "ismaster")
|
||||||
if(value=="yes")
|
{
|
||||||
uiRelation.ismaster=true;
|
if(value=="yes")
|
||||||
else
|
uiRelation.ismaster=true;
|
||||||
uiRelation.ismaster=false;
|
else
|
||||||
}
|
uiRelation.ismaster=false;
|
||||||
else if(prop== "haslimits")
|
}
|
||||||
{
|
else if(prop== "haslimits")
|
||||||
if(value=="yes")
|
{
|
||||||
uiRelation.haslimits=true;
|
if(value=="yes")
|
||||||
else
|
uiRelation.haslimits=true;
|
||||||
uiRelation.haslimits=false;
|
else
|
||||||
}
|
uiRelation.haslimits=false;
|
||||||
else if(prop== "button")
|
}
|
||||||
{
|
else if(prop== "button")
|
||||||
if(value=="save")
|
{
|
||||||
uiRelation.buttonType=save_button;
|
if(value=="save")
|
||||||
else if(value=="apply")
|
uiRelation.buttonType=save_button;
|
||||||
uiRelation.buttonType=apply_button;
|
else if(value=="apply")
|
||||||
else if(value=="reload")
|
uiRelation.buttonType=apply_button;
|
||||||
uiRelation.buttonType=reload_button;
|
else if(value=="reload")
|
||||||
else if(value=="default")
|
uiRelation.buttonType=reload_button;
|
||||||
uiRelation.buttonType=default_button;
|
else if(value=="default")
|
||||||
}
|
uiRelation.buttonType=default_button;
|
||||||
else if(prop== "buttongroup")
|
}
|
||||||
{
|
else if(prop== "buttongroup")
|
||||||
foreach(QString s,value.split(","))
|
{
|
||||||
{
|
foreach(QString s,value.split(","))
|
||||||
uiRelation.buttonGroup.append(s.toInt());
|
{
|
||||||
}
|
uiRelation.buttonGroup.append(s.toInt());
|
||||||
|
}
|
||||||
}
|
|
||||||
}
|
}
|
||||||
if(!uiRelation.buttonType==none)
|
}
|
||||||
{
|
if(!uiRelation.buttonType==none)
|
||||||
QPushButton * button=NULL;
|
{
|
||||||
switch(uiRelation.buttonType)
|
QPushButton * button=NULL;
|
||||||
{
|
switch(uiRelation.buttonType)
|
||||||
case save_button:
|
{
|
||||||
saveButtonWidget=qobject_cast<QPushButton *>(widget);
|
case save_button:
|
||||||
break;
|
saveButtonWidget=qobject_cast<QPushButton *>(widget);
|
||||||
case apply_button:
|
break;
|
||||||
applyButtonWidget=qobject_cast<QPushButton *>(widget);
|
case apply_button:
|
||||||
break;
|
applyButtonWidget=qobject_cast<QPushButton *>(widget);
|
||||||
case default_button:
|
break;
|
||||||
button=qobject_cast<QPushButton *>(widget);
|
case default_button:
|
||||||
if(button)
|
button=qobject_cast<QPushButton *>(widget);
|
||||||
addDefaultButton(button,uiRelation.buttonGroup.at(0));
|
if(button)
|
||||||
break;
|
addDefaultButton(button,uiRelation.buttonGroup.at(0));
|
||||||
case reload_button:
|
break;
|
||||||
button=qobject_cast<QPushButton *>(widget);
|
case reload_button:
|
||||||
if(button)
|
button=qobject_cast<QPushButton *>(widget);
|
||||||
addReloadButton(button,uiRelation.buttonGroup.at(0));
|
if(button)
|
||||||
break;
|
addReloadButton(button,uiRelation.buttonGroup.at(0));
|
||||||
default:
|
break;
|
||||||
break;
|
default:
|
||||||
}
|
break;
|
||||||
}
|
}
|
||||||
else if(uiRelation.ismaster)
|
}
|
||||||
{
|
else if(uiRelation.ismaster)
|
||||||
QWidget * wid=qobject_cast<QWidget *>(widget);
|
{
|
||||||
if(wid)
|
QWidget * wid=qobject_cast<QWidget *>(widget);
|
||||||
addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.haslimits,&uiRelation.buttonGroup);
|
if(wid)
|
||||||
}
|
addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.haslimits,&uiRelation.buttonGroup);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(saveButtonWidget && applyButtonWidget)
|
}
|
||||||
addApplySaveButtons(applyButtonWidget,saveButtonWidget);
|
if(saveButtonWidget && applyButtonWidget)
|
||||||
}
|
addApplySaveButtons(applyButtonWidget,saveButtonWidget);
|
||||||
|
}
|
||||||
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> * groups)
|
|
||||||
{
|
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> * groups)
|
||||||
foreach(objectToWidget * oTw,objOfInterest)
|
{
|
||||||
{
|
foreach(objectToWidget * oTw,objOfInterest)
|
||||||
bool addOTW=false;
|
{
|
||||||
if(oTw->widget==widget)
|
bool addOTW=false;
|
||||||
addOTW=true;
|
if(oTw->widget==widget)
|
||||||
else
|
addOTW=true;
|
||||||
{
|
else
|
||||||
foreach(shadow * sh, oTw->shadowsList)
|
{
|
||||||
{
|
foreach(shadow * sh, oTw->shadowsList)
|
||||||
if(sh->widget==widget)
|
{
|
||||||
addOTW=true;
|
if(sh->widget==widget)
|
||||||
}
|
addOTW=true;
|
||||||
}
|
}
|
||||||
if(addOTW)
|
}
|
||||||
{
|
if(addOTW)
|
||||||
foreach(int i,*groups)
|
{
|
||||||
{
|
foreach(int i,*groups)
|
||||||
if(defaultReloadGroups.contains(i))
|
{
|
||||||
{
|
if(defaultReloadGroups.contains(i))
|
||||||
defaultReloadGroups.value(i)->append(oTw);
|
{
|
||||||
}
|
defaultReloadGroups.value(i)->append(oTw);
|
||||||
else
|
}
|
||||||
{
|
else
|
||||||
defaultReloadGroups.insert(i,new QList<objectToWidget*>());
|
{
|
||||||
defaultReloadGroups.value(i)->append(oTw);
|
defaultReloadGroups.insert(i,new QList<objectToWidget*>());
|
||||||
}
|
defaultReloadGroups.value(i)->append(oTw);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
|
}
|
||||||
{
|
void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
|
||||||
button->setProperty("group",buttonGroup);
|
{
|
||||||
connect(button,SIGNAL(clicked()),this,SLOT(defaultButtonClicked()));
|
button->setProperty("group",buttonGroup);
|
||||||
}
|
connect(button,SIGNAL(clicked()),this,SLOT(defaultButtonClicked()));
|
||||||
void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup)
|
}
|
||||||
{
|
void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup)
|
||||||
button->setProperty("group",buttonGroup);
|
{
|
||||||
connect(button,SIGNAL(clicked()),this,SLOT(reloadButtonClicked()));
|
button->setProperty("group",buttonGroup);
|
||||||
}
|
connect(button,SIGNAL(clicked()),this,SLOT(reloadButtonClicked()));
|
||||||
void ConfigTaskWidget::defaultButtonClicked()
|
}
|
||||||
{
|
void ConfigTaskWidget::defaultButtonClicked()
|
||||||
int group=sender()->property("group").toInt();
|
{
|
||||||
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
|
int group=sender()->property("group").toInt();
|
||||||
foreach(objectToWidget * oTw,*list)
|
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
|
||||||
{
|
foreach(objectToWidget * oTw,*list)
|
||||||
if(!oTw->object)
|
{
|
||||||
continue;
|
if(!oTw->object)
|
||||||
UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone();
|
continue;
|
||||||
setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale,oTw->isLimited);
|
UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone();
|
||||||
}
|
setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale,oTw->isLimited);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
void ConfigTaskWidget::reloadButtonClicked()
|
|
||||||
{
|
void ConfigTaskWidget::reloadButtonClicked()
|
||||||
int group=sender()->property("group").toInt();
|
{
|
||||||
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
|
int group=sender()->property("group").toInt();
|
||||||
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( getObjectManager()->getObject(ObjectPersistence::NAME) );
|
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
|
||||||
QTimer * timeOut=new QTimer(this);
|
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( getObjectManager()->getObject(ObjectPersistence::NAME) );
|
||||||
QEventLoop * eventLoop=new QEventLoop(this);
|
QTimer * timeOut=new QTimer(this);
|
||||||
connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit()));
|
QEventLoop * eventLoop=new QEventLoop(this);
|
||||||
connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit()));
|
connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit()));
|
||||||
foreach(objectToWidget * oTw,*list)
|
connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit()));
|
||||||
{
|
foreach(objectToWidget * oTw,*list)
|
||||||
if (oTw->object != NULL)
|
{
|
||||||
{
|
if (oTw->object != NULL)
|
||||||
ObjectPersistence::DataFields data;
|
{
|
||||||
data.Operation = ObjectPersistence::OPERATION_LOAD;
|
ObjectPersistence::DataFields data;
|
||||||
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
|
data.Operation = ObjectPersistence::OPERATION_LOAD;
|
||||||
data.ObjectID = oTw->object->getObjID();
|
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
|
||||||
data.InstanceID = oTw->object->getInstID();
|
data.ObjectID = oTw->object->getObjID();
|
||||||
objper->setData(data);
|
data.InstanceID = oTw->object->getInstID();
|
||||||
objper->updated();
|
objper->setData(data);
|
||||||
timeOut->start(500);
|
objper->updated();
|
||||||
eventLoop->exec();
|
timeOut->start(500);
|
||||||
if(timeOut->isActive())
|
eventLoop->exec();
|
||||||
{
|
if(timeOut->isActive())
|
||||||
setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited);
|
{
|
||||||
}
|
setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited);
|
||||||
timeOut->stop();
|
}
|
||||||
}
|
timeOut->stop();
|
||||||
}
|
}
|
||||||
delete eventLoop;
|
}
|
||||||
delete timeOut;
|
delete eventLoop;
|
||||||
}
|
delete timeOut;
|
||||||
|
}
|
||||||
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* function)
|
|
||||||
{
|
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* function)
|
||||||
if(!widget)
|
{
|
||||||
return;
|
if(!widget)
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
return;
|
||||||
{
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
connect(cb,SIGNAL(currentIndexChanged(int)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(currentIndexChanged(int)),this,function);
|
||||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
}
|
||||||
{
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
connect(cb,SIGNAL(sliderMoved(int)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(sliderMoved(int)),this,function);
|
||||||
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
|
}
|
||||||
{
|
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
|
||||||
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,function);
|
||||||
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
|
}
|
||||||
{
|
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
|
||||||
connect(cb,SIGNAL(cellChanged(int,int)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(cellChanged(int,int)),this,function);
|
||||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
connect(cb,SIGNAL(valueChanged(int)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(valueChanged(int)),this,function);
|
||||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
connect(cb,SIGNAL(valueChanged(double)),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(valueChanged(double)),this,function);
|
||||||
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
}
|
||||||
{
|
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
||||||
connect(cb,SIGNAL(clicked()),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(clicked()),this,function);
|
||||||
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
|
}
|
||||||
{
|
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
|
||||||
connect(cb,SIGNAL(clicked()),this,function);
|
{
|
||||||
}
|
connect(cb,SIGNAL(clicked()),this,function);
|
||||||
else
|
}
|
||||||
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
else
|
||||||
|
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
||||||
}
|
|
||||||
|
}
|
||||||
bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,float scale)
|
|
||||||
{
|
bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,float scale)
|
||||||
if(!widget || !field)
|
{
|
||||||
return false;
|
if(!widget || !field)
|
||||||
QVariant ret=getVariantFromWidget(widget,scale);
|
return false;
|
||||||
if(ret.isValid())
|
QVariant ret=getVariantFromWidget(widget,scale);
|
||||||
{
|
if(ret.isValid())
|
||||||
field->setValue(ret,index);
|
{
|
||||||
return true;
|
field->setValue(ret,index);
|
||||||
}
|
return true;
|
||||||
{
|
}
|
||||||
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
{
|
||||||
return false;
|
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
||||||
}
|
return false;
|
||||||
}
|
}
|
||||||
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,float scale)
|
}
|
||||||
{
|
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,float scale)
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
{
|
||||||
{
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
return (QString)cb->currentText();
|
{
|
||||||
}
|
return (QString)cb->currentText();
|
||||||
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
|
}
|
||||||
{
|
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
|
||||||
return (QString)cb->text();
|
{
|
||||||
}
|
return (QString)cb->text();
|
||||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
return (double)(cb->value()* scale);
|
{
|
||||||
}
|
return (double)(cb->value()* scale);
|
||||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
return (int)(cb->value()* (int)scale);
|
{
|
||||||
}
|
return (int)(cb->value()* (int)scale);
|
||||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
}
|
||||||
{
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
return(int)(cb->value()* (int)scale);
|
{
|
||||||
}
|
return(int)(cb->value()* (int)scale);
|
||||||
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
}
|
||||||
{
|
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
||||||
return (bool)(cb->isChecked()?"TRUE":"FALSE");
|
{
|
||||||
}
|
return (bool)(cb->isChecked()?"TRUE":"FALSE");
|
||||||
else
|
}
|
||||||
return QVariant();
|
else
|
||||||
}
|
return QVariant();
|
||||||
|
}
|
||||||
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, float scale)
|
|
||||||
{
|
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, float scale)
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
{
|
||||||
{
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
cb->setCurrentIndex(cb->findText(value.toString()));
|
{
|
||||||
return true;
|
cb->setCurrentIndex(cb->findText(value.toString()));
|
||||||
}
|
return true;
|
||||||
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
|
}
|
||||||
{
|
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
|
||||||
cb->setText(value.toString());
|
{
|
||||||
return true;
|
cb->setText(value.toString());
|
||||||
}
|
return true;
|
||||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
cb->setValue(value.toDouble()/scale);
|
{
|
||||||
return true;
|
cb->setValue(value.toDouble()/scale);
|
||||||
}
|
return true;
|
||||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
cb->setValue(value.toInt()/(int)scale);
|
{
|
||||||
return true;
|
cb->setValue(value.toInt()/(int)scale);
|
||||||
}
|
return true;
|
||||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
}
|
||||||
{
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
cb->setValue(value.toInt()/(int)scale);
|
{
|
||||||
return true;
|
cb->setValue(value.toInt()/(int)scale);
|
||||||
}
|
return true;
|
||||||
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
}
|
||||||
{
|
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
||||||
cb->setChecked(value.toBool());
|
{
|
||||||
return true;
|
cb->setChecked(value.toBool());
|
||||||
}
|
return true;
|
||||||
else
|
}
|
||||||
return false;
|
else
|
||||||
}
|
return false;
|
||||||
|
}
|
||||||
bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,float scale,bool hasLimits)
|
|
||||||
{
|
bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,float scale,bool hasLimits)
|
||||||
if(!widget || !field)
|
{
|
||||||
return false;
|
if(!widget || !field)
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
return false;
|
||||||
{
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
if(cb->count()==0)
|
{
|
||||||
loadWidgetLimits(cb,field,index,hasLimits,scale);
|
if(cb->count()==0)
|
||||||
}
|
loadWidgetLimits(cb,field,index,hasLimits,scale);
|
||||||
QVariant var=field->getValue(index);
|
}
|
||||||
checkWidgetsLimits(widget,field,index,hasLimits,var,scale);
|
QVariant var=field->getValue(index);
|
||||||
bool ret=setWidgetFromVariant(widget,var,scale);
|
checkWidgetsLimits(widget,field,index,hasLimits,var,scale);
|
||||||
if(ret)
|
bool ret=setWidgetFromVariant(widget,var,scale);
|
||||||
return true;
|
if(ret)
|
||||||
else
|
return true;
|
||||||
{
|
else
|
||||||
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
{
|
||||||
return false;
|
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
|
||||||
}
|
return false;
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, float scale)
|
}
|
||||||
{
|
void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, float scale)
|
||||||
if(!hasLimits)
|
{
|
||||||
return;
|
if(!hasLimits)
|
||||||
qDebug()<<"check widget"<<widget->accessibleName()<<"value"<<value.toString()<<"result"<<field->isWithinLimits(value,index);
|
return;
|
||||||
if(!field->isWithinLimits(value,index))
|
qDebug()<<"check widget"<<widget->accessibleName()<<"value"<<value.toString()<<"result"<<field->isWithinLimits(value,index);
|
||||||
{
|
if(!field->isWithinLimits(value,index))
|
||||||
if(!widget->property("styleBackup").isValid())
|
{
|
||||||
widget->setProperty("styleBackup",widget->styleSheet());
|
if(!widget->property("styleBackup").isValid())
|
||||||
widget->setStyleSheet(outOfLimitsStyle);
|
widget->setProperty("styleBackup",widget->styleSheet());
|
||||||
widget->setProperty("wasOverLimits",(bool)true);
|
widget->setStyleSheet(outOfLimitsStyle);
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
widget->setProperty("wasOverLimits",(bool)true);
|
||||||
{
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
if(cb->findText(value.toString())==-1)
|
{
|
||||||
cb->addItem(value.toString());
|
if(cb->findText(value.toString())==-1)
|
||||||
}
|
cb->addItem(value.toString());
|
||||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
if(value.toDouble()/scale>cb->maximum())
|
{
|
||||||
{
|
if(value.toDouble()/scale>cb->maximum())
|
||||||
cb->setMaximum(value.toDouble()/scale);
|
{
|
||||||
}
|
cb->setMaximum(value.toDouble()/scale);
|
||||||
else if(value.toDouble()/scale<cb->minimum())
|
}
|
||||||
{
|
else if(value.toDouble()/scale<cb->minimum())
|
||||||
cb->setMinimum(value.toDouble()/scale);
|
{
|
||||||
}
|
cb->setMinimum(value.toDouble()/scale);
|
||||||
|
}
|
||||||
}
|
|
||||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
}
|
||||||
{
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
if(value.toInt()/scale>cb->maximum())
|
{
|
||||||
{
|
if(value.toInt()/scale>cb->maximum())
|
||||||
cb->setMaximum(value.toInt()/scale);
|
{
|
||||||
}
|
cb->setMaximum(value.toInt()/scale);
|
||||||
else if(value.toInt()/scale<cb->minimum())
|
}
|
||||||
{
|
else if(value.toInt()/scale<cb->minimum())
|
||||||
cb->setMinimum(value.toInt()/scale);
|
{
|
||||||
}
|
cb->setMinimum(value.toInt()/scale);
|
||||||
}
|
}
|
||||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
}
|
||||||
{
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
if(value.toInt()/scale>cb->maximum())
|
{
|
||||||
{
|
if(value.toInt()/scale>cb->maximum())
|
||||||
cb->setMaximum(value.toInt()/scale);
|
{
|
||||||
}
|
cb->setMaximum(value.toInt()/scale);
|
||||||
else if(value.toInt()/scale<cb->minimum())
|
}
|
||||||
{
|
else if(value.toInt()/scale<cb->minimum())
|
||||||
cb->setMinimum(value.toInt()/scale);
|
{
|
||||||
}
|
cb->setMinimum(value.toInt()/scale);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
}
|
|
||||||
else if(widget->property("wasOverLimits").isValid())
|
}
|
||||||
{
|
else if(widget->property("wasOverLimits").isValid())
|
||||||
qDebug()<<"1wasOverLimits";
|
{
|
||||||
if(widget->property("wasOverLimits").toBool())
|
qDebug()<<"1wasOverLimits";
|
||||||
{
|
if(widget->property("wasOverLimits").toBool())
|
||||||
qDebug()<<"2";
|
{
|
||||||
widget->setProperty("wasOverLimits",(bool)false);
|
qDebug()<<"2";
|
||||||
if(widget->property("styleBackup").isValid())
|
widget->setProperty("wasOverLimits",(bool)false);
|
||||||
{
|
if(widget->property("styleBackup").isValid())
|
||||||
qDebug()<<"3";
|
{
|
||||||
QString style=widget->property("styleBackup").toString();
|
qDebug()<<"3";
|
||||||
qDebug()<<"STYLE"<<style;
|
QString style=widget->property("styleBackup").toString();
|
||||||
widget->setStyleSheet(style);
|
qDebug()<<"STYLE"<<style;
|
||||||
}
|
widget->setStyleSheet(style);
|
||||||
loadWidgetLimits(widget,field,index,hasLimits,scale);
|
}
|
||||||
}
|
loadWidgetLimits(widget,field,index,hasLimits,scale);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,float scale)
|
}
|
||||||
{
|
void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,float scale)
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
{
|
||||||
{
|
if(!widget || !field)
|
||||||
cb->clear();
|
return;
|
||||||
QStringList option=field->getOptions();
|
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
if(hasLimits)
|
{
|
||||||
{
|
cb->clear();
|
||||||
foreach(QString str,option)
|
QStringList option=field->getOptions();
|
||||||
{
|
if(hasLimits)
|
||||||
if(field->isWithinLimits(str,index))
|
{
|
||||||
cb->addItem(str);
|
foreach(QString str,option)
|
||||||
}
|
{
|
||||||
}
|
if(field->isWithinLimits(str,index))
|
||||||
else
|
cb->addItem(str);
|
||||||
cb->addItems(option);
|
}
|
||||||
}
|
}
|
||||||
if(!hasLimits)
|
else
|
||||||
return;
|
cb->addItems(option);
|
||||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
}
|
||||||
{
|
if(!hasLimits)
|
||||||
if(field->getMaxLimit(index).isValid())
|
return;
|
||||||
{
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
cb->setMaximum(field->getMaxLimit(index).toDouble()/scale);
|
{
|
||||||
}
|
if(field->getMaxLimit(index).isValid())
|
||||||
if(field->getMinLimit(index).isValid())
|
{
|
||||||
{
|
cb->setMaximum(field->getMaxLimit(index).toDouble()/scale);
|
||||||
cb->setMinimum(field->getMinLimit(index).toDouble()/scale);
|
}
|
||||||
}
|
if(field->getMinLimit(index).isValid())
|
||||||
}
|
{
|
||||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
cb->setMinimum(field->getMinLimit(index).toDouble()/scale);
|
||||||
{
|
}
|
||||||
if(field->getMaxLimit(index).isValid())
|
}
|
||||||
{
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
{
|
||||||
}
|
if(field->getMaxLimit(index).isValid())
|
||||||
if(field->getMinLimit(index).isValid())
|
{
|
||||||
{
|
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
||||||
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
}
|
||||||
}
|
if(field->getMinLimit(index).isValid())
|
||||||
}
|
{
|
||||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
||||||
{
|
}
|
||||||
if(field->getMaxLimit(index).isValid())
|
}
|
||||||
{
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
{
|
||||||
}
|
if(field->getMaxLimit(index).isValid())
|
||||||
if(field->getMinLimit(index).isValid())
|
{
|
||||||
{
|
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
||||||
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
}
|
||||||
}
|
if(field->getMinLimit(index).isValid())
|
||||||
}
|
{
|
||||||
}
|
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
||||||
|
}
|
||||||
/**
|
}
|
||||||
@}
|
}
|
||||||
@}
|
|
||||||
*/
|
/**
|
||||||
|
@}
|
||||||
|
@}
|
||||||
|
*/
|
@ -1,158 +1,159 @@
|
|||||||
/**
|
/**
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*
|
*
|
||||||
* @file configtaskwidget.h
|
* @file configtaskwidget.h
|
||||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
* @addtogroup GCSPlugins GCS Plugins
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
* @{
|
* @{
|
||||||
* @addtogroup ConfigPlugin Config Plugin
|
* @addtogroup ConfigPlugin Config Plugin
|
||||||
* @{
|
* @{
|
||||||
* @brief The Configuration Gadget used to update settings in the firmware (task widget)
|
* @brief The Configuration Gadget used to update settings in the firmware (task widget)
|
||||||
*****************************************************************************/
|
*****************************************************************************/
|
||||||
/*
|
/*
|
||||||
* This program is free software; you can redistribute it and/or modify
|
* This program is free software; you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation; either version 3 of the License, or
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This program is distributed in the hope that it will be useful, but
|
* This program is distributed in the hope that it will be useful, but
|
||||||
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
* for more details.
|
* for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License along
|
* You should have received a copy of the GNU General Public License along
|
||||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
*/
|
*/
|
||||||
#ifndef CONFIGTASKWIDGET_H
|
#ifndef CONFIGTASKWIDGET_H
|
||||||
#define CONFIGTASKWIDGET_H
|
#define CONFIGTASKWIDGET_H
|
||||||
|
|
||||||
|
|
||||||
#include "extensionsystem/pluginmanager.h"
|
#include "extensionsystem/pluginmanager.h"
|
||||||
#include "uavobjectmanager.h"
|
#include "uavobjectmanager.h"
|
||||||
#include "uavobject.h"
|
#include "uavobject.h"
|
||||||
#include "uavobjectutilmanager.h"
|
#include "uavobjectutilmanager.h"
|
||||||
#include <QQueue>
|
#include <QQueue>
|
||||||
#include <QtGui/QWidget>
|
#include <QtGui/QWidget>
|
||||||
#include <QList>
|
#include <QList>
|
||||||
#include <QLabel>
|
#include <QLabel>
|
||||||
#include "smartsavebutton.h"
|
#include "smartsavebutton.h"
|
||||||
#include "mixercurvewidget.h"
|
#include "mixercurvewidget.h"
|
||||||
#include <QTableWidget>
|
#include <QTableWidget>
|
||||||
#include <QDoubleSpinBox>
|
#include <QDoubleSpinBox>
|
||||||
#include <QSpinBox>
|
#include <QSpinBox>
|
||||||
#include <QCheckBox>
|
#include <QCheckBox>
|
||||||
#include <QPushButton>
|
#include <QPushButton>
|
||||||
|
#include "uavobjectwidgetutils_global.h"
|
||||||
class ConfigTaskWidget: public QWidget
|
|
||||||
{
|
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget
|
||||||
Q_OBJECT
|
{
|
||||||
|
Q_OBJECT
|
||||||
public:
|
|
||||||
struct shadow
|
public:
|
||||||
{
|
struct shadow
|
||||||
QWidget * widget;
|
{
|
||||||
float scale;
|
QWidget * widget;
|
||||||
bool isLimited;
|
float scale;
|
||||||
};
|
bool isLimited;
|
||||||
struct objectToWidget
|
};
|
||||||
{
|
struct objectToWidget
|
||||||
UAVObject * object;
|
{
|
||||||
UAVObjectField * field;
|
UAVObject * object;
|
||||||
QWidget * widget;
|
UAVObjectField * field;
|
||||||
int index;
|
QWidget * widget;
|
||||||
float scale;
|
int index;
|
||||||
bool isLimited;
|
float scale;
|
||||||
QList<shadow *> shadowsList;
|
bool isLimited;
|
||||||
};
|
QList<shadow *> shadowsList;
|
||||||
|
};
|
||||||
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button};
|
|
||||||
struct uiRelationAutomation
|
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button};
|
||||||
{
|
struct uiRelationAutomation
|
||||||
QString objname;
|
{
|
||||||
QString fieldname;
|
QString objname;
|
||||||
QString element;
|
QString fieldname;
|
||||||
int scale;
|
QString element;
|
||||||
bool ismaster;
|
int scale;
|
||||||
bool haslimits;
|
bool ismaster;
|
||||||
buttonTypeEnum buttonType;
|
bool haslimits;
|
||||||
QList<int> buttonGroup;
|
buttonTypeEnum buttonType;
|
||||||
};
|
QList<int> buttonGroup;
|
||||||
|
};
|
||||||
ConfigTaskWidget(QWidget *parent = 0);
|
|
||||||
~ConfigTaskWidget();
|
ConfigTaskWidget(QWidget *parent = 0);
|
||||||
|
~ConfigTaskWidget();
|
||||||
void saveObjectToSD(UAVObject *obj);
|
|
||||||
UAVObjectManager* getObjectManager();
|
void saveObjectToSD(UAVObject *obj);
|
||||||
static double listMean(QList<double> list);
|
UAVObjectManager* getObjectManager();
|
||||||
|
static double listMean(QList<double> list);
|
||||||
void addUAVObject(QString objectName);
|
|
||||||
void addWidget(QWidget * widget);
|
void addUAVObject(QString objectName);
|
||||||
|
void addWidget(QWidget * widget);
|
||||||
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
|
||||||
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,float scale,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
||||||
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
|
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,float scale,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
||||||
|
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
|
||||||
//BUTTONS//
|
|
||||||
void addApplySaveButtons(QPushButton * update,QPushButton * save);
|
//BUTTONS//
|
||||||
void addReloadButton(QPushButton * button,int buttonGroup);
|
void addApplySaveButtons(QPushButton * update,QPushButton * save);
|
||||||
void addDefaultButton(QPushButton * button,int buttonGroup);
|
void addReloadButton(QPushButton * button,int buttonGroup);
|
||||||
//////////
|
void addDefaultButton(QPushButton * button,int buttonGroup);
|
||||||
|
//////////
|
||||||
void addWidgetToDefaultReloadGroups(QWidget * widget, QList<int> *groups);
|
|
||||||
|
void addWidgetToDefaultReloadGroups(QWidget * widget, QList<int> *groups);
|
||||||
bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,float shadowScale=1,bool shadowIsLimited=false);
|
|
||||||
bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false, QList<int> *defaultReloadGroups=NULL);
|
bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,float shadowScale=1,bool shadowIsLimited=false);
|
||||||
|
bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false, QList<int> *defaultReloadGroups=NULL);
|
||||||
void autoLoadWidgets();
|
|
||||||
|
void autoLoadWidgets();
|
||||||
bool isDirty();
|
|
||||||
void setDirty(bool value);
|
bool isDirty();
|
||||||
|
void setDirty(bool value);
|
||||||
bool allObjectsUpdated();
|
|
||||||
|
bool allObjectsUpdated();
|
||||||
public slots:
|
|
||||||
void onAutopilotDisconnect();
|
public slots:
|
||||||
void onAutopilotConnect();
|
void onAutopilotDisconnect();
|
||||||
void invalidateObjects();
|
void onAutopilotConnect();
|
||||||
void removeObject(UAVObject*);
|
void invalidateObjects();
|
||||||
void removeAllObjects();
|
void removeObject(UAVObject*);
|
||||||
signals:
|
void removeAllObjects();
|
||||||
void objectAdded(UAVObject*);
|
signals:
|
||||||
void objectRemoved(UAVObject*);
|
void objectAdded(UAVObject*);
|
||||||
private slots:
|
void objectRemoved(UAVObject*);
|
||||||
void objectUpdated(UAVObject*);
|
private slots:
|
||||||
void defaultButtonClicked();
|
void objectUpdated(UAVObject*);
|
||||||
void reloadButtonClicked();
|
void defaultButtonClicked();
|
||||||
private:
|
void reloadButtonClicked();
|
||||||
bool isConnected;
|
private:
|
||||||
QStringList objectsList;
|
bool isConnected;
|
||||||
QList <objectToWidget*> objOfInterest;
|
QStringList objectsList;
|
||||||
ExtensionSystem::PluginManager *pm;
|
QList <objectToWidget*> objOfInterest;
|
||||||
UAVObjectManager *objManager;
|
ExtensionSystem::PluginManager *pm;
|
||||||
smartSaveButton *smartsave;
|
UAVObjectManager *objManager;
|
||||||
QMap<UAVObject *,bool> objectUpdates;
|
smartSaveButton *smartsave;
|
||||||
QMap<int,QList<objectToWidget*> *> defaultReloadGroups;
|
QMap<UAVObject *,bool> objectUpdates;
|
||||||
QMap<QWidget *,objectToWidget*> shadowsList;
|
QMap<int,QList<objectToWidget*> *> defaultReloadGroups;
|
||||||
bool dirty;
|
QMap<QWidget *,objectToWidget*> shadowsList;
|
||||||
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, float scale);
|
bool dirty;
|
||||||
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, float scale, bool hasLimits);
|
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, float scale);
|
||||||
QVariant getVariantFromWidget(QWidget *widget, float scale);
|
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, float scale, bool hasLimits);
|
||||||
bool setWidgetFromVariant(QWidget *widget,QVariant value,float scale);
|
QVariant getVariantFromWidget(QWidget *widget, float scale);
|
||||||
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
bool setWidgetFromVariant(QWidget *widget,QVariant value,float scale);
|
||||||
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, float sclale);
|
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
||||||
QString outOfLimitsStyle;
|
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, float sclale);
|
||||||
protected slots:
|
QString outOfLimitsStyle;
|
||||||
virtual void disableObjUpdates();
|
protected slots:
|
||||||
virtual void enableObjUpdates();
|
virtual void disableObjUpdates();
|
||||||
virtual void clearDirty();
|
virtual void enableObjUpdates();
|
||||||
virtual void widgetsContentsChanged();
|
virtual void clearDirty();
|
||||||
virtual void populateWidgets();
|
virtual void widgetsContentsChanged();
|
||||||
virtual void refreshWidgetsValues();
|
virtual void populateWidgets();
|
||||||
virtual void updateObjectsFromWidgets();
|
virtual void refreshWidgetsValues();
|
||||||
protected:
|
virtual void updateObjectsFromWidgets();
|
||||||
virtual void enableControls(bool enable);
|
protected:
|
||||||
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, float scale);
|
virtual void enableControls(bool enable);
|
||||||
};
|
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, float scale);
|
||||||
|
};
|
||||||
#endif // CONFIGTASKWIDGET_H
|
|
||||||
|
#endif // CONFIGTASKWIDGET_H
|
@ -33,9 +33,9 @@
|
|||||||
#include <QtSvg/QGraphicsSvgItem>
|
#include <QtSvg/QGraphicsSvgItem>
|
||||||
#include "mixercurvepoint.h"
|
#include "mixercurvepoint.h"
|
||||||
#include "mixercurveline.h"
|
#include "mixercurveline.h"
|
||||||
|
#include "uavobjectwidgetutils_global.h"
|
||||||
|
|
||||||
|
class UAVOBJECTWIDGETUTILS_EXPORT MixerCurveWidget : public QGraphicsView
|
||||||
class MixerCurveWidget : public QGraphicsView
|
|
||||||
{
|
{
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
|
|
@ -0,0 +1,6 @@
|
|||||||
|
include(uavobjectwidgetutils_dependencies.pri)
|
||||||
|
|
||||||
|
# Add the include path to the built-in uavobject include files.
|
||||||
|
INCLUDEPATH += $$PWD
|
||||||
|
|
||||||
|
LIBS *= -l$$qtLibraryName(UAVObjectWidgetUtils)
|
@ -0,0 +1,22 @@
|
|||||||
|
TEMPLATE = lib
|
||||||
|
TARGET = UAVObjectWidgetUtils
|
||||||
|
DEFINES += UAVOBJECTWIDGETUTILS_LIBRARY
|
||||||
|
QT += svg
|
||||||
|
include(../../openpilotgcsplugin.pri)
|
||||||
|
include(uavobjectwidgetutils_dependencies.pri)
|
||||||
|
HEADERS += uavobjectwidgetutils_global.h \
|
||||||
|
uavobjectwidgetutilsplugin.h \
|
||||||
|
configtaskwidget.h \
|
||||||
|
mixercurvewidget.h \
|
||||||
|
mixercurvepoint.h \
|
||||||
|
mixercurveline.h \
|
||||||
|
smartsavebutton.h
|
||||||
|
SOURCES += uavobjectwidgetutilsplugin.cpp \
|
||||||
|
configtaskwidget.cpp \
|
||||||
|
mixercurvewidget.cpp \
|
||||||
|
mixercurvepoint.cpp \
|
||||||
|
mixercurveline.cpp \
|
||||||
|
smartsavebutton.cpp
|
||||||
|
|
||||||
|
|
||||||
|
OTHER_FILES += UAVObjectWidgetUtils.pluginspec
|
@ -0,0 +1,6 @@
|
|||||||
|
include(../../plugins/coreplugin/coreplugin.pri)
|
||||||
|
include(../../libs/utils/utils.pri)
|
||||||
|
include(../../plugins/uavobjects/uavobjects.pri)
|
||||||
|
include(../uavobjectutil/uavobjectutil.pri)
|
||||||
|
include(../uavsettingsimportexport/uavsettingsimportexport.pri)
|
||||||
|
include(../uavtalk/uavtalk.pri)
|
@ -0,0 +1,40 @@
|
|||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
*
|
||||||
|
* @file uavobjectwidgetutils_global.h
|
||||||
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
|
* @see The GNU Public License (GPL) Version 3
|
||||||
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
|
* @{
|
||||||
|
* @addtogroup UAVObjectWidgetUtilsPlugin
|
||||||
|
* @{
|
||||||
|
* @brief The UAVUObjectWidgetUtils GCS plugin
|
||||||
|
*****************************************************************************/
|
||||||
|
/*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
|
* for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License along
|
||||||
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef UAVOBJECTWIDGETUTILS_GLOBAL_H
|
||||||
|
#define UAVOBJECTWIDGETUTILS_GLOBAL_H
|
||||||
|
|
||||||
|
#include <QtCore/qglobal.h>
|
||||||
|
|
||||||
|
#if defined(UAVOBJECTWIDGETUTILS_LIBRARY)
|
||||||
|
# define UAVOBJECTWIDGETUTILS_EXPORT Q_DECL_EXPORT
|
||||||
|
#else
|
||||||
|
# define UAVOBJECTWIDGETUTILS_EXPORT Q_DECL_IMPORT
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
@ -0,0 +1,55 @@
|
|||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
*
|
||||||
|
* @file uavobjectutilplugin.cpp
|
||||||
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
|
* @see The GNU Public License (GPL) Version 3
|
||||||
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
|
* @{
|
||||||
|
* @addtogroup UAVObjectUtilPlugin UAVObjectUtil Plugin
|
||||||
|
* @{
|
||||||
|
* @brief The UAVUObjectUtil GCS plugin
|
||||||
|
*****************************************************************************/
|
||||||
|
/*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
|
* for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License along
|
||||||
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "uavobjectwidgetutilsplugin.h"
|
||||||
|
|
||||||
|
UAVObjectWidgetUtilsPlugin::UAVObjectWidgetUtilsPlugin()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
UAVObjectWidgetUtilsPlugin::~UAVObjectWidgetUtilsPlugin()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void UAVObjectWidgetUtilsPlugin::extensionsInitialized()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
bool UAVObjectWidgetUtilsPlugin::initialize(const QStringList & arguments, QString * errorString)
|
||||||
|
{
|
||||||
|
Q_UNUSED(arguments)
|
||||||
|
Q_UNUSED(errorString)
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void UAVObjectWidgetUtilsPlugin::shutdown()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
Q_EXPORT_PLUGIN(UAVObjectWidgetUtilsPlugin)
|
@ -0,0 +1,48 @@
|
|||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
*
|
||||||
|
* @file uavobjectutilplugin.h
|
||||||
|
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||||
|
* @see The GNU Public License (GPL) Version 3
|
||||||
|
* @addtogroup GCSPlugins GCS Plugins
|
||||||
|
* @{
|
||||||
|
* @addtogroup UAVObjectUtilPlugin UAVObjectUtil Plugin
|
||||||
|
* @{
|
||||||
|
* @brief The UAVUObjectUtil GCS plugin
|
||||||
|
*****************************************************************************/
|
||||||
|
/*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
|
||||||
|
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
|
||||||
|
* for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License along
|
||||||
|
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||||
|
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||||
|
*/
|
||||||
|
#ifndef UAVOBJECTWIDGETUTILSPLUGIN_H
|
||||||
|
#define UAVOBJECTWIDGETUTILSPLUGIN_H
|
||||||
|
|
||||||
|
#include "uavobjectwidgetutils_global.h"
|
||||||
|
#include <extensionsystem/iplugin.h>
|
||||||
|
#include <QtPlugin>
|
||||||
|
|
||||||
|
class UAVOBJECTWIDGETUTILS_EXPORT UAVObjectWidgetUtilsPlugin: public ExtensionSystem::IPlugin
|
||||||
|
{
|
||||||
|
Q_OBJECT
|
||||||
|
|
||||||
|
public:
|
||||||
|
UAVObjectWidgetUtilsPlugin();
|
||||||
|
~UAVObjectWidgetUtilsPlugin();
|
||||||
|
|
||||||
|
void extensionsInitialized();
|
||||||
|
bool initialize(const QStringList & arguments, QString * errorString);
|
||||||
|
void shutdown();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
Loading…
x
Reference in New Issue
Block a user