Commit b25ca6f1 authored by Don Gagne's avatar Don Gagne
Browse files

Merge pull request #2261 from DonLakeFlyer/RawEdit

Mission Item raw/friendly edit support, plus more [merge after Stable 2.8]
parents 8e681c09 77c2342d
......@@ -95,6 +95,8 @@
<file alias="Signal100.svg">src/ui/toolbar/Images/Signal100.svg</file>
<file alias="Yield.svg">src/ui/toolbar/Images/Yield.svg</file>
<file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file>
</qresource>
<qresource prefix="/res">
......
......@@ -247,8 +247,9 @@ HEADERS += \
src/Joystick/JoystickManager.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/QGC.h \
src/QGCApplication.h \
src/QGCComboBox.h \
......@@ -290,7 +291,6 @@ HEADERS += \
src/ui/toolbar/MainToolBarController.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/uas/UASMessageView.h \
src/MissionItem.h \
src/AutoPilotPlugins/PX4/PX4AirframeLoader.h \
src/QmlControls/QGCImageProvider.h \
......@@ -362,8 +362,9 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/QGC.cc \
src/QGCApplication.cc \
src/QGCComboBox.cc \
......@@ -401,7 +402,6 @@ SOURCES += \
src/ui/toolbar/MainToolBarController.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/uas/UASMessageView.cc \
src/MissionItem.cc \
src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc \
src/QmlControls/QGCImageProvider.cc \
......@@ -470,9 +470,9 @@ HEADERS += \
src/FactSystem/FactSystemTestBase.h \
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/MissionItemTest.h \
src/MissionManager/MissionControllerTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionItemTest.h \
src/MissionManager/MissionManagerTest.h \
src/qgcunittest/GeoTest.h \
src/qgcunittest/FileDialogTest.h \
......@@ -493,9 +493,9 @@ SOURCES += \
src/FactSystem/FactSystemTestBase.cc \
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/MissionItemTest.cc \
src/MissionManager/MissionControllerTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionItemTest.cc \
src/MissionManager/MissionManagerTest.cc \
src/qgcunittest/GeoTest.cc \
src/qgcunittest/FileDialogTest.cc \
......
......@@ -36,7 +36,6 @@
<file alias="QGroundControl/Controls/MainToolBarIndicators.qml">src/ui/toolbar/MainToolBarIndicators.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/QmlControls/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemSummary.qml">src/QmlControls/MissionItemSummary.qml</file>
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
......@@ -100,4 +99,7 @@
<file alias="test.qml">src/test.qml</file>
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
</qresource>
<qresource prefix="/json">
<file alias="MavCmdInfo.json">src/MissionManager/MavCmdInfo.json</file>
</qresource>
</RCC>
......@@ -31,7 +31,7 @@
Fact::Fact(QObject* parent)
: QObject(parent)
, _componentId(-1)
, _value(0)
, _rawValue(0)
, _type(FactMetaData::valueTypeInt32)
, _metaData(NULL)
{
......@@ -43,7 +43,7 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
: QObject(parent)
, _name(name)
, _componentId(componentId)
, _value(0)
, _rawValue(0)
, _type(type)
, _metaData(NULL)
{
......@@ -61,7 +61,7 @@ const Fact& Fact::operator=(const Fact& other)
{
_name = other._name;
_componentId = other._componentId;
_value = other._value;
_rawValue = other._rawValue;
_type = other._type;
if (_metaData && other._metaData) {
......@@ -80,28 +80,58 @@ void Fact::forceSetValue(const QVariant& value)
QString errorString;
if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) {
_value.setValue(typedValue);
emit valueChanged(_value);
emit _containerValueChanged(_value);
_rawValue.setValue(_metaData->cookedTranslator()(typedValue));
emit valueChanged(typedValue);
emit _containerValueChanged(typedValue);
}
} else {
qWarning() << "Meta data pointer missing";
}
}
void Fact::setValue(const QVariant& value)
void Fact::setRawValue(const QVariant& value)
{
if (_metaData) {
QVariant typedValue;
QString errorString;
if (_metaData->convertAndValidate(value, true /* convertOnly */, typedValue, errorString)) {
if (typedValue != _value) {
_value.setValue(typedValue);
emit valueChanged(_value);
emit _containerValueChanged(_value);
if (typedValue != _rawValue) {
_rawValue.setValue(typedValue);
emit valueChanged(this->value());
emit _containerValueChanged(this->value());
}
}
} else {
qWarning() << "Meta data pointer missing";
}
}
void Fact::setValue(const QVariant& value)
{
if (_metaData) {
setRawValue(_metaData->cookedTranslator()(value));
} else {
qWarning() << "Meta data pointer missing";
}
}
void Fact::setEnumStringValue(const QString& value)
{
if (_metaData) {
int index = _metaData->enumStrings().indexOf(value);
if (index != -1) {
setValue(_metaData->enumValues()[index]);
}
} else {
qWarning() << "Meta data pointer missing";
}
}
void Fact::setEnumIndex(int index)
{
if (_metaData) {
setValue(_metaData->enumValues()[index]);
} else {
qWarning() << "Meta data pointer missing";
}
......@@ -109,9 +139,9 @@ void Fact::setValue(const QVariant& value)
void Fact::_containerSetValue(const QVariant& value)
{
_value = value;
emit valueChanged(_value);
emit vehicleUpdated(_value);
_rawValue = value;
emit valueChanged(_rawValue);
emit vehicleUpdated(_rawValue);
}
QString Fact::name(void) const
......@@ -126,7 +156,63 @@ int Fact::componentId(void) const
QVariant Fact::value(void) const
{
return _value;
if (_metaData) {
return _metaData->rawTranslator()(_rawValue);
} else {
qWarning() << "Meta data pointer missing";
return _rawValue;
}
}
QString Fact::enumStringValue(void) const
{
if (_metaData) {
int enumIndex = this->enumIndex();
if (enumIndex > 0 && enumIndex < _metaData->enumStrings().count()) {
return _metaData->enumStrings()[enumIndex];
}
} else {
qWarning() << "Meta data pointer missing";
}
return QString();
}
int Fact::enumIndex(void) const
{
if (_metaData) {
int index = 0;
foreach (QVariant enumValue, _metaData->enumValues()) {
if (enumValue == value()) {
return index;
}
index ++;
}
} else {
qWarning() << "Meta data pointer missing";
}
return -1;
}
QStringList Fact::enumStrings(void) const
{
if (_metaData) {
return _metaData->enumStrings();
} else {
qWarning() << "Meta data pointer missing";
return QStringList();
}
}
QVariantList Fact::enumValues(void) const
{
if (_metaData) {
return _metaData->enumValues();
} else {
qWarning() << "Meta data pointer missing";
return QVariantList();
}
}
QString Fact::_variantToString(const QVariant& variant) const
......@@ -279,6 +365,7 @@ QString Fact::group(void) const
void Fact::setMetaData(FactMetaData* metaData)
{
_metaData = metaData;
emit valueChanged(value());
}
bool Fact::valueEqualsDefault(void) const
......
......@@ -47,55 +47,66 @@ public:
const Fact& operator=(const Fact& other);
Q_PROPERTY(int componentId READ componentId CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
Q_PROPERTY(QString defaultValueString READ defaultValueString CONSTANT)
Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(int enumIndex READ enumIndex WRITE setEnumIndex NOTIFY valueChanged)
Q_PROPERTY(QStringList enumStrings READ enumStrings CONSTANT)
Q_PROPERTY(QString enumStringValue READ enumStringValue WRITE setEnumStringValue NOTIFY valueChanged)
Q_PROPERTY(QVariantList enumValues READ enumValues CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(QString minString READ minString CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(QString maxString READ maxString CONSTANT)
Q_PROPERTY(bool maxIsDefaultForType READ maxIsDefaultForType CONSTANT)
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(QString minString READ minString CONSTANT)
Q_PROPERTY(bool minIsDefaultForType READ minIsDefaultForType CONSTANT)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged)
Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
/// Convert and validate value
/// @param convertOnly true: validate type conversion only, false: validate against meta data as well
Q_INVOKABLE QString validate(const QString& value, bool convertOnly);
// Property system methods
QString name(void) const;
int componentId(void) const;
QVariant value(void) const;
QString valueString(void) const;
QVariant defaultValue(void) const;
QString defaultValueString(void) const;
bool defaultValueAvailable(void) const;
bool valueEqualsDefault(void) const;
QString shortDescription(void) const;
QString longDescription(void) const;
QString units(void) const;
QVariant min(void) const;
QString minString(void) const;
bool minIsDefaultForType(void) const;
QVariant max(void) const;
QString maxString(void) const;
bool maxIsDefaultForType(void) const;
QString group(void) const;
int decimalPlaces(void) const;
FactMetaData::ValueType_t type(void) const;
void setValue(const QVariant& value);
int componentId (void) const;
int decimalPlaces (void) const;
QVariant defaultValue (void) const;
bool defaultValueAvailable (void) const;
QString defaultValueString (void) const;
int enumIndex (void) const;
QStringList enumStrings (void) const;
QString enumStringValue (void) const;
QVariantList enumValues (void) const;
QString group (void) const;
QString longDescription (void) const;
QVariant max (void) const;
QString maxString (void) const;
bool maxIsDefaultForType (void) const;
QVariant min (void) const;
QString minString (void) const;
bool minIsDefaultForType (void) const;
QString name (void) const;
QVariant rawValue (void) const { return _rawValue; } /// value prior to translation, careful
QString shortDescription (void) const;
FactMetaData::ValueType_t type (void) const;
QString units (void) const;
QVariant value (void) const;
QString valueString (void) const;
bool valueEqualsDefault (void) const;
void setRawValue (const QVariant& value);
void setValue (const QVariant& value);
void setEnumIndex (int index);
void setEnumStringValue (const QString& value);
// C++ methods
/// Sets and sends new value to vehicle even if value is the same
void forceSetValue(const QVariant& value);
......@@ -127,7 +138,7 @@ private:
QString _name;
int _componentId;
QVariant _value;
QVariant _rawValue;
FactMetaData::ValueType_t _type;
FactMetaData* _metaData;
};
......
......@@ -8,6 +8,17 @@ import QGroundControl.Controls 1.0
QGCComboBox {
property Fact fact: Fact { }
currentIndex: fact.value
onActivated: fact.value = index
property bool indexModel: true ///< true: model must be specifed, selected index is fact value, false: use enum meta data
model: fact.enumStrings
currentIndex: indexModel ? fact.value : fact.enumIndex
onActivated: {
if (indexModel) {
fact.value = index
} else {
fact.enumIndex = index
}
}
}
......@@ -33,19 +33,18 @@
QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog")
FactPanelController::FactPanelController(void) :
_factPanel(NULL)
FactPanelController::FactPanelController(void)
: _vehicle(NULL)
, _uas(NULL)
, _autopilot(NULL)
, _factPanel(NULL)
{
_vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
Q_ASSERT(_vehicle);
if (_vehicle) {
_uas = _vehicle->uas();
Q_ASSERT(_uas);
_autopilot = _vehicle->autopilotPlugin();
Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->parametersReady());
Q_ASSERT(!_autopilot->missingParameters());
}
// Do a delayed check for the _factPanel finally being set correctly from Qml
QTimer::singleShot(1000, this, &FactPanelController::_checkForMissingFactPanel);
......@@ -114,7 +113,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name
bool noMissingFacts = true;
foreach (QString name, names) {
if (!_autopilot->parameterExists(componentId, name)) {
if (_autopilot && !_autopilot->parameterExists(componentId, name)) {
_reportMissingParameter(componentId, name);
noMissingFacts = false;
}
......@@ -132,7 +131,7 @@ void FactPanelController::_checkForMissingFactPanel(void)
Fact* FactPanelController::getParameterFact(int componentId, const QString& name)
{
if (_autopilot->parameterExists(componentId, name)) {
if (_autopilot && _autopilot->parameterExists(componentId, name)) {
Fact* fact = _autopilot->getParameterFact(componentId, name);
QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership);
return fact;
......@@ -144,7 +143,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
bool FactPanelController::parameterExists(int componentId, const QString& name)
{
return _autopilot->parameterExists(componentId, name);
return _autopilot ? _autopilot->parameterExists(componentId, name) : false;
}
void FactPanelController::_showInternalError(const QString& errorMsg)
......
......@@ -34,30 +34,34 @@
FactMetaData::FactMetaData(QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(valueTypeInt32)
, _decimalPlaces(defaultDecimalPlaces)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _group("*Default Group")
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
, _min(_minForType())
, _minIsDefaultForType(true)
, _rawTranslator(defaultTranslator)
, _cookedTranslator(defaultTranslator)
{
}
FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
: QObject(parent)
, _group("*Default Group")
, _type(type)
, _decimalPlaces(defaultDecimalPlaces)
, _defaultValue(0)
, _defaultValueAvailable(false)
, _min(_minForType())
, _group("*Default Group")
, _max(_maxForType())
, _minIsDefaultForType(true)
, _maxIsDefaultForType(true)
, _decimalPlaces(defaultDecimalPlaces)
, _min(_minForType())
, _minIsDefaultForType(true)
, _rawTranslator(defaultTranslator)
, _cookedTranslator(defaultTranslator)
{
}
......@@ -70,15 +74,23 @@ FactMetaData::FactMetaData(const FactMetaData& other, QObject* parent)
const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
{
_group = other._group;
_type = other._type;
_decimalPlaces = other._decimalPlaces;
_defaultValue = other._defaultValue;
_defaultValueAvailable = other._defaultValueAvailable;
_min = other._min;
_enumStrings = other._enumStrings;
_enumValues = other._enumValues;
_group = other._group;
_longDescription = other._longDescription;
_max = other._max;
_minIsDefaultForType = other._minIsDefaultForType;
_maxIsDefaultForType = other._maxIsDefaultForType;
_decimalPlaces = other._decimalPlaces;
_min = other._min;
_minIsDefaultForType = other._minIsDefaultForType;
_name = other._name;
_shortDescription = other._shortDescription;
_type = other._type;
_units = other._units;
_rawTranslator = other._rawTranslator;
_cookedTranslator = other._cookedTranslator;
return *this;
}
......@@ -229,3 +241,20 @@ bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, Q
return convertOk && errorString.isEmpty();
}
void FactMetaData::setEnumInfo(const QStringList& strings, const QVariantList& values)
{
if (strings.count() != values.count()) {
qWarning() << "Count mismatch strings:values" << strings.count() << values.count();
return;
}
_enumStrings = strings;
_enumValues = values;
}
void FactMetaData::setTranslators(Translator rawTranslator, Translator cookedTranslator)
{
_rawTranslator = rawTranslator;
_cookedTranslator = cookedTranslator;
}
......@@ -52,37 +52,46 @@ public:
valueTypeDouble
} ValueType_t;
typedef QVariant (*Translator)(const QVariant& from);
FactMetaData(QObject* parent = NULL);
FactMetaData(ValueType_t type, QObject* parent = NULL);
FactMetaData(const FactMetaData& other, QObject* parent = NULL);
const FactMetaData& operator=(const FactMetaData& other);
// Property accessors
QString name(void) const { return _name; }
QString group(void) const { return _group; }
ValueType_t type(void) const { return _type; }
QVariant defaultValue(void) const;
bool defaultValueAvailable(void) const { return _defaultValueAvailable; }
QString shortDescription(void) const { return _shortDescription; }
QString longDescription(void) const { return _longDescription;}
QString units(void) const { return _units; }
QVariant min(void) const { return _min; }
QVariant max(void) const { return _max; }
bool minIsDefaultForType(void) const { return _minIsDefaultForType; }
bool maxIsDefaultForType(void) const { return _maxIsDefaultForType; }
int decimalPlaces(void) const { return _decimalPlaces; }
// Property setters
void setName(const QString& name) { _name = name; }
void setGroup(const QString& group) { _group = group; }
void setDefaultValue(const QVariant& defaultValue);
int decimalPlaces (void) const { return _decimalPlaces; }
QVariant defaultValue (void) const;
bool defaultValueAvailable (void) const { return _defaultValueAvailable; }
QStringList enumStrings (void) const { return _enumStrings; }
QVariantList enumValues (void) const { return _enumValues; }
QString group (void) const { return _group; }
QString longDescription (void) const { return _longDescription;}
QVariant max (void) const { return _max; }
bool maxIsDefaultForType (void) const { return _maxIsDefaultForType; }
QVariant min (void) const { return _min; }
bool minIsDefaultForType (void) const { return _minIsDefaultForType; }
QString name (void) const { return _name; }
QString shortDescription (void) const { return _shortDescription; }
ValueType_t type (void) const { return _type; }
QString units (void) const { return _units; }
Translator rawTranslator (void) const { return _rawTranslator; }
Translator cookedTranslator (void) const { return _cookedTranslator; }
void setDecimalPlaces (int decimalPlaces) { _decimalPlaces = decimalPlaces; }
void setDefaultValue (const QVariant& defaultValue);
void setEnumInfo (const QStringList& strings, const QVariantList& values);
void setGroup (const QString& group) { _group = group; }
void setLongDescription (const QString& longDescription) { _longDescription = longDescription;}
void setMax (const QVariant& max);
void setMin (const QVariant& max);
void setName (const QString& name) { _name = name; }
void setShortDescription(const QString& shortDescription) { _shortDescription = shortDescription; }
void setLongDescription(const QString& longDescription) { _longDescription = longDescription;}
void setUnits(const QString& units) { _units = units; }
void setMin(const QVariant& max);
void setMax(const QVariant& max);
void setDecimalPlaces(int decimalPlaces) { _decimalPlaces = decimalPlaces; }
void setUnits (const QString& units) { _units = units; }
void setTranslators(Translator rawTranslator, Translator cookedTranslator);
static QVariant defaultTranslator(const QVariant& from) { return from; }
/// Converts the specified value, validating against meta data
/// @param value Value to convert, can be string
......@@ -98,19 +107,23 @@ private:
QVariant _minForType(void) const;
QVariant _maxForType(void) const;
QString _name;
QString _group;
ValueType_t _type;
ValueType_t _type; // must be first for correct constructor init
int _decimalPlaces;
QVariant _defaultValue;
bool _defaultValueAvailable;
QString _shortDescription;
QStringList _enumStrings;
QVariantList _enumValues;
QString _group;
QString _longDescription;
QString _units;
QVariant _min;
QVariant _max;
bool _minIsDefaultForType;
bool _maxIsDefaultForType;
int _decimalPlaces;
QVariant _min;
bool _minIsDefaultForType;
QString _name;
QString _shortDescription;
QString _units;
Translator _rawTranslator;
Translator _cookedTranslator;
};
#endif
......@@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact)
{
_parameterMetaData.addMetaDataToFact(fact);
}
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
// FIXME: Temp list, just dup of PX4
list << MAV_CMD_NAV_WAYPOINT << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME
<< MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_CONDITION_DELAY << MAV_CMD_DO_JUMP;
return list;
}
......@@ -91,6 +91,7 @@ public:
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
protected:
/// All access to singleton is through stack specific implementation
......
......@@ -109,6 +109,9 @@ public:
/// Adds the parameter meta data to the Fact
virtual void addMetaDataToFact(Fact* fact) = 0;
/// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void) = 0;
};
#endif
......@@ -118,3 +118,9 @@ void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact)
FactMetaData* metaData = new FactMetaData(fact->type(), fact);
fact->setMetaData(metaData);
}
QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
return QList<MAV_CMD>();
}
......@@ -47,6 +47,7 @@ public:
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
};
#endif
......@@ -207,3 +207,15 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact)
{
_parameterMetaData.addMetaDataToFact(fact);
}
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> list;
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME
<< MAV_CMD_NAV_ROI
<< MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
<< MAV_CMD_DO_JUMP << MAV_CMD_DO_SET_SERVO;
return list;
}
......@@ -47,6 +47,7 @@ public:
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
private:
PX4ParameterMetaData _parameterMetaData;
......
......@@ -43,7 +43,7 @@ Item {
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
property real avaiableHeight: parent.height
property real availableHeight: parent.height
property bool interactive: true
readonly property bool isBackgroundDark: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true
......@@ -213,7 +213,7 @@ Item {
anchors.right: parent.right
anchors.left: parent.left
anchors.bottom: parent.bottom
height: avaiableHeight
height: availableHeight
}
}
......@@ -41,6 +41,7 @@ QGCView {
id: _root
viewPanel: panel
topDialogMargin: height - mainWindow.availableHeight
// zOrder comes from the Loader in MainWindow.qml
z: QGroundControl.zOrderTopMost
......@@ -148,10 +149,6 @@ QGCView {
latitude: mainWindow.tabletPosition.latitude
longitude: mainWindow.tabletPosition.longitude
Component.onCompleted: {
console.log("Init coordinate " + mainWindow.tabletPosition.latitude)
}
readonly property real animationDuration: 500
Behavior on zoomLevel {
......@@ -211,7 +208,6 @@ QGCView {
property var missionItem
property var missionItemIndicator
property real heading: missionItem ? missionItem.heading : 0
readonly property real _radius: ScreenTools.defaultFontPixelHeight * 4
readonly property real _arrowHeight: ScreenTools.defaultFontPixelHeight
......@@ -328,10 +324,8 @@ QGCView {
onClicked: setCurrentItem(object.sequenceNumber)
Connections {
target: object
onIsCurrentItemChanged: {
function updateItemIndicator()
{
if (object.isCurrentItem) {
_root.showDistance(object)
if (object.specifiesCoordinate) {
......@@ -350,6 +344,12 @@ QGCView {
}
}
}
Connections {
target: object
onIsCurrentItemChanged: updateItemIndicator()
onCommandChanged: updateItemIndicator()
}
// These are the non-coordinate child mission items attached to this item
......@@ -380,7 +380,7 @@ QGCView {
// Mission Item Editor
Item {
id: missionItemEditor
height: mainWindow.avaiableHeight
height: mainWindow.availableHeight
anchors.bottom: parent.bottom
anchors.right: parent.right
width: _rightPanelWidth
......@@ -389,11 +389,10 @@ QGCView {
z: QGroundControl.zOrderTopMost
ListView {
id: missionItemSummaryList
anchors.fill: parent
spacing: _margin / 2
orientation: ListView.Vertical
model: controller.canEdit ? controller.missionItems : 0
model: controller.missionItems
property real _maxItemHeight: 0
......@@ -416,14 +415,6 @@ QGCView {
}
}
} // ListView
QGCLabel {
anchors.fill: parent
visible: !controller.canEdit
wrapMode: Text.WordWrap
text: "The set of mission items you have loaded cannot be edited by QGroundControl. " +
"You will only be able to save these to a file, or send them to a vehicle."
}
} // Item - Mission Item editor
/*
......
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL 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.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionItem_H
#define MissionItem_H
#include <QObject>
#include <QString>
#include <QtQml>
#include <QTextStream>
#include <QGeoCoordinate>
#include "QGCMAVLink.h"
#include "QGC.h"
#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
class MissionItem : public QObject
{
Q_OBJECT
public:
MissionItem(QObject *parent = 0,
int sequenceNumber = 0,
QGeoCoordinate coordiante = QGeoCoordinate(),
int action = MAV_CMD_NAV_WAYPOINT,
double param1 = 0.0,
double param2 = defaultAcceptanceRadius,
double param3 = defaultLoiterOrbitRadius,
double param4 = defaultHeading,
bool autocontinue = true,
bool isCurrentItem = false,
int frame = MAV_FRAME_GLOBAL_RELATIVE_ALT);
MissionItem(const MissionItem& other, QObject* parent = NULL);
~MissionItem();
const MissionItem& operator=(const MissionItem& other);
/// Returns true if the item has been modified since the last time dirty was false
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY commandChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(bool specifiesHeading READ specifiesHeading NOTIFY commandChanged)
Q_PROPERTY(double heading READ headingDegrees WRITE setHeadingDegrees NOTIFY headingDegreesChanged)
Q_PROPERTY(QStringList commandNames READ commandNames CONSTANT)
Q_PROPERTY(QString commandName READ commandName NOTIFY commandChanged)
Q_PROPERTY(QString commandDescription READ commandDescription NOTIFY commandChanged)
Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged)
Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged)
Q_PROPERTY(QmlObjectListModel* textFieldFacts READ textFieldFacts NOTIFY commandChanged)
Q_PROPERTY(QmlObjectListModel* checkboxFacts READ checkboxFacts NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
/// true: this item is being used as a home position indicator
Q_PROPERTY(bool homePosition READ homePosition CONSTANT)
/// true: home position should be shown
Q_PROPERTY(bool homePositionValid READ homePositionValid WRITE setHomePositionValid NOTIFY homePositionValidChanged)
/// Distance to previous waypoint, set by UI controller
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged)
// Property accesors
int sequenceNumber(void) const { return _sequenceNumber; }
void setSequenceNumber(int sequenceNumber);
bool isCurrentItem(void) const { return _isCurrentItem; }
void setIsCurrentItem(bool isCurrentItem);
bool specifiesCoordinate(void) const;
QGeoCoordinate coordinate(void) const;
void setCoordinate(const QGeoCoordinate& coordinate);
bool specifiesHeading(void) const;
double headingDegrees(void) const;
void setHeadingDegrees(double headingDegrees);
// This is public for unit testing
double _yawRadians(void) const;
QStringList commandNames(void);
QString commandName(void);
QString commandDescription(void);
int commandByIndex(void);
void setCommandByIndex(int index);
MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; };
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
QStringList valueLabels(void);
QStringList valueStrings(void);
QmlObjectListModel* textFieldFacts(void);
QmlObjectListModel* checkboxFacts(void);
bool dirty(void) { return _dirty; }
void setDirty(bool dirty);
QmlObjectListModel* childItems(void) { return &_childItems; }
bool homePosition(void) { return _homePositionSpecialCase; }
bool homePositionValid(void) { return _homePositionValid; }
void setHomePositionValid(bool homePositionValid);
double distance(void) { return _distance; }
void setDistance(double distance);
// C++ only methods
/// Returns true if this item can be edited in the ui
bool canEdit(void);
double latitude(void) const { return _latitudeFact->value().toDouble(); }
double longitude(void) const { return _longitudeFact->value().toDouble(); }
double altitude(void) const { return _altitudeFact->value().toDouble(); }
void setLatitude(double latitude);
void setLongitude(double longitude);
void setAltitude(double altitude);
double x(void) const { return latitude(); }
double y(void) const { return longitude(); }
double z(void) const { return altitude(); }
void setX(double x);
void setY(double y);
void setZ(double z);
bool autoContinue() const {
return _autocontinue;
}
double loiterOrbitRadius() const {
return _loiterOrbitRadiusFact->value().toDouble();
}
double acceptanceRadius() const {
return param2();
}
double holdTime() const {
return param1();
}
double param1() const {
return _param1Fact->value().toDouble();
}
double param2() const {
return _param2Fact->value().toDouble();
}
double param3() const {
return loiterOrbitRadius();
}
double param4() const {
return _yawRadians();
}
double param5() const {
return latitude();
}
double param6() const {
return longitude();
}
double param7() const {
return altitude();
}
// MAV_FRAME
int frame() const;
// MAV_CMD
int command() const {
return _command;
}
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
/** @brief Get the time this waypoint was reached */
quint64 reachedTime() const { return _reachedTime; }
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
void setHomePositionSpecialCase(bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
bool relativeAltitude(void) { return _frame == MAV_FRAME_GLOBAL_RELATIVE_ALT; }
static const double defaultPitch;
static const double defaultHeading;
static const double defaultAltitude;
static const double defaultAcceptanceRadius;
static const double defaultLoiterOrbitRadius;
static const double defaultLoiterTurns;
signals:
void sequenceNumberChanged(int sequenceNumber);
void isCurrentItemChanged(bool isCurrentItem);
void coordinateChanged(const QGeoCoordinate& coordinate);
void headingDegreesChanged(double heading);
void dirtyChanged(bool dirty);
void homePositionValidChanged(bool homePostionValid);
void distanceChanged(float distance);
void frameChanged(int frame);
void commandNameChanged(QString type);
void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void valueLabelsChanged(QStringList valueLabels);
void valueStringsChanged(QStringList valueStrings);
bool autoContinueChanged(bool autoContinue);
public:
/** @brief Set the waypoint action */
void setAction (int _action);
void setFrame (int _frame);
void setAutocontinue(bool autoContinue);
void setCurrent (bool _current);
void setLoiterOrbitRadius (double radius);
void setParam1 (double _param1);
void setParam2 (double _param2);
void setParam3 (double param3);
void setParam4 (double param4);
void setParam5 (double param5);
void setParam6 (double param6);
void setParam7 (double param7);
void setAcceptanceRadius(double radius);
void setHoldTime (int holdTime);
void setHoldTime (double holdTime);
/** @brief Set waypoint as reached */
void setReached () { _reachedTime = QGC::groundTimeMilliseconds(); }
/** @brief Wether this waypoint has been reached yet */
bool isReached () { return (_reachedTime > 0); }
private slots:
void _factValueChanged(QVariant value);
void _coordinateFactChanged(QVariant value);
void _headingDegreesFactChanged(QVariant value);
void _altitudeRelativeToHomeFactChanged(QVariant value);
private:
QString _oneDecimalString(double value);
void _connectSignals(void);
void _setYawRadians(double yawRadians);
private:
typedef struct {
MAV_CMD command;
const char* name;
} MavCmd2Name_t;
int _sequenceNumber;
int _frame;
MavlinkQmlSingleton::Qml_MAV_CMD _command;
bool _autocontinue;
bool _isCurrentItem;
quint64 _reachedTime;
double _distance;
Fact* _latitudeFact;
Fact* _longitudeFact;
Fact* _altitudeFact;
Fact* _headingDegreesFact;
Fact* _loiterOrbitRadiusFact;
Fact* _param1Fact;
Fact* _param2Fact;
Fact* _altitudeRelativeToHomeFact;
FactMetaData* _pitchMetaData;
FactMetaData* _acceptanceRadiusMetaData;
FactMetaData* _holdTimeMetaData;
FactMetaData* _loiterTurnsMetaData;
FactMetaData* _loiterSecondsMetaData;
FactMetaData* _delaySecondsMetaData;
FactMetaData* _jumpSequenceMetaData;
FactMetaData* _jumpRepeatMetaData;
bool _dirty;
bool _homePositionSpecialCase; ///< true: this item is being used as a ui home position indicator
bool _homePositionValid; ///< true: home psition should be displayed
/// This is used to reference any subsequent mission items which do not specify a coordinate.
QmlObjectListModel _childItems;
static const int _cMavCmd2Name = 9;
static const MavCmd2Name_t _rgMavCmd2Name[_cMavCmd2Name];
};
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
QDebug operator<<(QDebug dbg, const MissionItem* missionItem);
#endif
Supports Markdown
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