Commit 74e2c247 authored by Don Gagne's avatar Don Gagne

Merge pull request #1872 from DonLakeFlyer/MissionWork2

Add relative altitude support
parents 66d45cc9 dc90f4b9
...@@ -153,14 +153,6 @@ QGCView { ...@@ -153,14 +153,6 @@ QGCView {
onTriggered: controller.setMissionItems() onTriggered: controller.setMissionItems()
} }
MenuItem {
text: "Load mission items from disk"
}
MenuItem {
text: "Save mission items to disk"
}
} }
} }
...@@ -198,6 +190,17 @@ QGCView { ...@@ -198,6 +190,17 @@ QGCView {
onMoveDown: controller.moveDown(object.sequenceNumber) onMoveDown: controller.moveDown(object.sequenceNumber)
} }
} // ListView } // ListView
QGCLabel {
anchors.topMargin: _verticalMargin
anchors.left: parent.left
anchors.right: parent.right
anchors.top: toolsButton.bottom
anchors.bottom: parent.bottom
visible: controller.missionItems.count == 0
wrapMode: Text.WordWrap
text: "Click in the map to add Mission Items"
}
} // Item } // Item
} // Rectangle - mission item list } // Rectangle - mission item list
} // Item - split view container } // Item - split view container
......
...@@ -34,6 +34,23 @@ This file is part of the QGROUNDCONTROL project ...@@ -34,6 +34,23 @@ This file is part of the QGROUNDCONTROL project
#include "MissionItem.h" #include "MissionItem.h"
QDebug operator<<(QDebug dbg, const MissionItem& missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem.coordinate() << ")";
return dbg;
}
QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
{
QDebugStateSaver saver(dbg);
dbg.nospace() << "MissionItem(" << missionItem->coordinate() << ")";
return dbg;
}
const MissionItem::MavCmd2Name_t MissionItem::_rgMavCmd2Name[_cMavCmd2Name] = { const MissionItem::MavCmd2Name_t MissionItem::_rgMavCmd2Name[_cMavCmd2Name] = {
{ MAV_CMD_NAV_WAYPOINT, "Waypoint" }, { MAV_CMD_NAV_WAYPOINT, "Waypoint" },
{ MAV_CMD_NAV_LOITER_UNLIM, "Loiter" }, { MAV_CMD_NAV_LOITER_UNLIM, "Loiter" },
...@@ -59,20 +76,24 @@ MissionItem::MissionItem(QObject* parent, ...@@ -59,20 +76,24 @@ MissionItem::MissionItem(QObject* parent,
int command) int command)
: QObject(parent) : QObject(parent)
, _sequenceNumber(sequenceNumber) , _sequenceNumber(sequenceNumber)
, _coordinate(coordinate)
, _frame(frame)
, _command((MavlinkQmlSingleton::Qml_MAV_CMD)command) , _command((MavlinkQmlSingleton::Qml_MAV_CMD)command)
, _autocontinue(autocontinue) , _autocontinue(autocontinue)
, _isCurrentItem(isCurrentItem) , _isCurrentItem(isCurrentItem)
, _reachedTime(0) , _reachedTime(0)
, _yawRadiansFact(NULL) , _yawRadiansFact(NULL)
{ {
_latitudeFact = new Fact(0, "Latitude:", FactMetaData::valueTypeDouble, this);
_longitudeFact = new Fact(0, "Longitude:", FactMetaData::valueTypeDouble, this);
_altitudeFact = new Fact(0, "Altitude:", FactMetaData::valueTypeDouble, this);
_yawRadiansFact = new Fact(0, "Heading:", FactMetaData::valueTypeDouble, this);
_loiterOrbitRadiusFact = new Fact(0, "Radius:", FactMetaData::valueTypeDouble, this);
_param1Fact = new Fact(0, QString(), FactMetaData::valueTypeDouble, this);
_param2Fact = new Fact(0, QString(), FactMetaData::valueTypeDouble, this);
_altitudeRelativeToHomeFact = new Fact(0, "Altitude is relative to home", FactMetaData::valueTypeDouble, this);
_yawRadiansFact = new Fact(0, "Heading:", FactMetaData::valueTypeDouble, this); setFrame(frame);
_loiterOrbitRadiusFact = new Fact(0, "Radius:", FactMetaData::valueTypeDouble, this);
_param1Fact = new Fact(0, QString(), FactMetaData::valueTypeDouble, this);
_param2Fact = new Fact(0, QString(), FactMetaData::valueTypeDouble, this);
setCoordinate(coordinate);
setParam1(param1); setParam1(param1);
setParam2(param2); setParam2(param2);
setYawRadians(param4); setYawRadians(param4);
...@@ -80,11 +101,20 @@ MissionItem::MissionItem(QObject* parent, ...@@ -80,11 +101,20 @@ MissionItem::MissionItem(QObject* parent,
// FIXME: Need to fill out more meta data // FIXME: Need to fill out more meta data
FactMetaData* yawMetaData = new FactMetaData(FactMetaData::valueTypeDouble, this); FactMetaData* latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _latitudeFact);
yawMetaData->setUnits("degrees"); latitudeMetaData->setUnits("deg");
FactMetaData* longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _longitudeFact);
longitudeMetaData->setUnits("deg");
FactMetaData* altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _altitudeFact);
altitudeMetaData->setUnits("meters");
FactMetaData* yawMetaData = new FactMetaData(FactMetaData::valueTypeDouble, _yawRadiansFact);
yawMetaData->setUnits("deg");
_pitchMetaData = new FactMetaData(FactMetaData::valueTypeDouble, this); _pitchMetaData = new FactMetaData(FactMetaData::valueTypeDouble, this);
_pitchMetaData->setUnits("degrees"); _pitchMetaData->setUnits("deg");
_acceptanceRadiusMetaData = new FactMetaData(FactMetaData::valueTypeDouble, this); _acceptanceRadiusMetaData = new FactMetaData(FactMetaData::valueTypeDouble, this);
_acceptanceRadiusMetaData->setUnits("meters"); _acceptanceRadiusMetaData->setUnits("meters");
...@@ -110,6 +140,9 @@ MissionItem::MissionItem(QObject* parent, ...@@ -110,6 +140,9 @@ MissionItem::MissionItem(QObject* parent,
_jumpRepeatMetaData = new FactMetaData(FactMetaData::valueTypeInt32, this); _jumpRepeatMetaData = new FactMetaData(FactMetaData::valueTypeInt32, this);
_jumpRepeatMetaData->setUnits("count"); _jumpRepeatMetaData->setUnits("count");
_latitudeFact->setMetaData(latitudeMetaData);
_longitudeFact->setMetaData(longitudeMetaData);
_altitudeFact->setMetaData(altitudeMetaData);
_yawRadiansFact->setMetaData(yawMetaData); _yawRadiansFact->setMetaData(yawMetaData);
_loiterOrbitRadiusFact->setMetaData(loiterOrbitRadiusMetaData); _loiterOrbitRadiusFact->setMetaData(loiterOrbitRadiusMetaData);
} }
...@@ -117,10 +150,14 @@ MissionItem::MissionItem(QObject* parent, ...@@ -117,10 +150,14 @@ MissionItem::MissionItem(QObject* parent,
MissionItem::MissionItem(const MissionItem& other, QObject* parent) MissionItem::MissionItem(const MissionItem& other, QObject* parent)
: QObject(parent) : QObject(parent)
{ {
_yawRadiansFact = new Fact(this); _latitudeFact = new Fact(this);
_loiterOrbitRadiusFact = new Fact(this); _longitudeFact = new Fact(this);
_param1Fact = new Fact(this); _altitudeFact = new Fact(this);
_param2Fact = new Fact(this); _yawRadiansFact = new Fact(this);
_loiterOrbitRadiusFact = new Fact(this);
_param1Fact = new Fact(this);
_param2Fact = new Fact(this);
_altitudeRelativeToHomeFact = new Fact(this);
_pitchMetaData = new FactMetaData(this); _pitchMetaData = new FactMetaData(this);
...@@ -141,14 +178,17 @@ MissionItem::~MissionItem() ...@@ -141,14 +178,17 @@ MissionItem::~MissionItem()
const MissionItem& MissionItem::operator=(const MissionItem& other) const MissionItem& MissionItem::operator=(const MissionItem& other)
{ {
_sequenceNumber = other._sequenceNumber; _sequenceNumber = other._sequenceNumber;
_isCurrentItem = other._isCurrentItem; _isCurrentItem = other._isCurrentItem;
_coordinate = other._coordinate; _frame = other._frame;
_frame = other._frame; _command = other._command;
_command = other._command; _autocontinue = other._autocontinue;
_autocontinue = other._autocontinue; _reachedTime = other._reachedTime;
_reachedTime = other._reachedTime; _altitudeRelativeToHomeFact = other._altitudeRelativeToHomeFact;
*_latitudeFact = *other._latitudeFact;
*_longitudeFact = *other._longitudeFact;
*_altitudeFact = *other._altitudeFact;
*_yawRadiansFact = *other._yawRadiansFact; *_yawRadiansFact = *other._yawRadiansFact;
*_loiterOrbitRadiusFact = *other._loiterOrbitRadiusFact; *_loiterOrbitRadiusFact = *other._loiterOrbitRadiusFact;
*_param1Fact = *other._param1Fact; *_param1Fact = *other._param1Fact;
...@@ -190,7 +230,7 @@ bool MissionItem::load(QTextStream &loadStream) ...@@ -190,7 +230,7 @@ bool MissionItem::load(QTextStream &loadStream)
if (wpParams.size() == 12) { if (wpParams.size() == 12) {
setSequenceNumber(wpParams[0].toInt()); setSequenceNumber(wpParams[0].toInt());
setIsCurrentItem(wpParams[1].toInt() == 1 ? true : false); setIsCurrentItem(wpParams[1].toInt() == 1 ? true : false);
_frame = (MAV_FRAME) wpParams[2].toInt(); setFrame(wpParams[2].toInt());
setAction(wpParams[3].toInt()); setAction(wpParams[3].toInt());
setParam1(wpParams[4].toDouble()); setParam1(wpParams[4].toDouble());
setParam2(wpParams[5].toDouble()); setParam2(wpParams[5].toDouble());
...@@ -239,9 +279,9 @@ void MissionItem::setZ(double z) ...@@ -239,9 +279,9 @@ void MissionItem::setZ(double z)
void MissionItem::setLatitude(double lat) void MissionItem::setLatitude(double lat)
{ {
if (_coordinate.latitude() != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) if (_latitudeFact->value().toDouble() != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{ {
_coordinate.setLatitude(lat); _latitudeFact->setValue(lat);
emit changed(this); emit changed(this);
emit coordinateChanged(coordinate()); emit coordinateChanged(coordinate());
} }
...@@ -249,9 +289,9 @@ void MissionItem::setLatitude(double lat) ...@@ -249,9 +289,9 @@ void MissionItem::setLatitude(double lat)
void MissionItem::setLongitude(double lon) void MissionItem::setLongitude(double lon)
{ {
if (_coordinate.longitude() != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) if (_longitudeFact->value().toDouble() != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{ {
_coordinate.setLongitude(lon); _longitudeFact->setValue(lon);
emit changed(this); emit changed(this);
emit coordinateChanged(coordinate()); emit coordinateChanged(coordinate());
} }
...@@ -259,9 +299,9 @@ void MissionItem::setLongitude(double lon) ...@@ -259,9 +299,9 @@ void MissionItem::setLongitude(double lon)
void MissionItem::setAltitude(double altitude) void MissionItem::setAltitude(double altitude)
{ {
if (_coordinate.altitude() != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) if (_altitudeFact->value().toDouble() != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)))
{ {
_coordinate.setAltitude(altitude); _altitudeFact->setValue(altitude);
emit changed(this); emit changed(this);
emit valueStringsChanged(valueStrings()); emit valueStringsChanged(valueStrings());
emit coordinateChanged(coordinate()); emit coordinateChanged(coordinate());
...@@ -283,15 +323,24 @@ void MissionItem::setAction(int /*MAV_CMD*/ action) ...@@ -283,15 +323,24 @@ void MissionItem::setAction(int /*MAV_CMD*/ action)
emit changed(this); emit changed(this);
emit commandNameChanged(commandName()); emit commandNameChanged(commandName());
emit commandChanged((MavlinkQmlSingleton::Qml_MAV_CMD)_command); emit commandChanged((MavlinkQmlSingleton::Qml_MAV_CMD)_command);
emit specifiesCoordinateChanged(specifiesCoordinate());
emit valueLabelsChanged(valueLabels()); emit valueLabelsChanged(valueLabels());
emit valueStringsChanged(valueStrings()); emit valueStringsChanged(valueStrings());
} }
} }
int MissionItem::frame(void) const
{
if (_altitudeRelativeToHomeFact->value().toBool()) {
return MAV_FRAME_GLOBAL_RELATIVE_ALT;
} else {
return _frame;
}
}
void MissionItem::setFrame(int /*MAV_FRAME*/ frame) void MissionItem::setFrame(int /*MAV_FRAME*/ frame)
{ {
if (_frame != frame) { if (_frame != frame) {
_altitudeRelativeToHomeFact->setValue(_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT);
_frame = frame; _frame = frame;
emit changed(this); emit changed(this);
} }
...@@ -350,29 +399,17 @@ void MissionItem::setParam4(double param4) ...@@ -350,29 +399,17 @@ void MissionItem::setParam4(double param4)
void MissionItem::setParam5(double param5) void MissionItem::setParam5(double param5)
{ {
if (_coordinate.latitude() != param5) { setLatitude(param5);
_coordinate.setLatitude(param5);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
} }
void MissionItem::setParam6(double param6) void MissionItem::setParam6(double param6)
{ {
if (_coordinate.longitude() != param6) { setLongitude(param6);
_coordinate.setLongitude(param6);
emit changed(this);
emit valueStringsChanged(valueStrings());
}
} }
void MissionItem::setParam7(double param7) void MissionItem::setParam7(double param7)
{ {
if (_coordinate.altitude() != param7) { setAltitude(param7);
_coordinate.setAltitude(param7);
emit valueStringsChanged(valueStrings());
emit changed(this);
}
} }
void MissionItem::setLoiterOrbitRadius(double radius) void MissionItem::setLoiterOrbitRadius(double radius)
...@@ -509,7 +546,7 @@ QStringList MissionItem::valueStrings(void) ...@@ -509,7 +546,7 @@ QStringList MissionItem::valueStrings(void)
switch (_command) { switch (_command) {
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(yawDegrees()) << _oneDecimalString(param2()) << _oneDecimalString(param1()); list << _oneDecimalString(_altitudeFact->value().toDouble()) << _oneDecimalString(yawDegrees()) << _oneDecimalString(param2()) << _oneDecimalString(param1());
break; break;
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
list << _oneDecimalString(yawRadians() * (180.0 / M_PI)) << _oneDecimalString(loiterOrbitRadius()); list << _oneDecimalString(yawRadians() * (180.0 / M_PI)) << _oneDecimalString(loiterOrbitRadius());
...@@ -523,10 +560,10 @@ QStringList MissionItem::valueStrings(void) ...@@ -523,10 +560,10 @@ QStringList MissionItem::valueStrings(void)
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
break; break;
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(yawRadians() * (180.0 / M_PI)); list << _oneDecimalString(_altitudeFact->value().toDouble()) << _oneDecimalString(yawRadians() * (180.0 / M_PI));
break; break;
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
list << _oneDecimalString(_coordinate.altitude()) << _oneDecimalString(yawRadians() * (180.0 / M_PI)) << _oneDecimalString(param1()); list << _oneDecimalString(_altitudeFact->value().toDouble()) << _oneDecimalString(yawRadians() * (180.0 / M_PI)) << _oneDecimalString(param1());
break; break;
case MAV_CMD_CONDITION_DELAY: case MAV_CMD_CONDITION_DELAY:
list << _oneDecimalString(param1()); list << _oneDecimalString(param1());
...@@ -541,13 +578,6 @@ QStringList MissionItem::valueStrings(void) ...@@ -541,13 +578,6 @@ QStringList MissionItem::valueStrings(void)
return list; return list;
} }
void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
_coordinate = coordinate;
emit coordinateChanged(coordinate);
emit changed(this);
}
QStringList MissionItem::commandNames(void) { QStringList MissionItem::commandNames(void) {
QStringList list; QStringList list;
...@@ -579,7 +609,7 @@ void MissionItem::setCommandByIndex(int index) ...@@ -579,7 +609,7 @@ void MissionItem::setCommandByIndex(int index)
setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)_rgMavCmd2Name[index].command); setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)_rgMavCmd2Name[index].command);
} }
QmlObjectListModel* MissionItem::facts(void) QmlObjectListModel* MissionItem::textFieldFacts(void)
{ {
QmlObjectListModel* model = new QmlObjectListModel(this); QmlObjectListModel* model = new QmlObjectListModel(this);
...@@ -589,17 +619,26 @@ QmlObjectListModel* MissionItem::facts(void) ...@@ -589,17 +619,26 @@ QmlObjectListModel* MissionItem::facts(void)
_param2Fact->setMetaData(_acceptanceRadiusMetaData); _param2Fact->setMetaData(_acceptanceRadiusMetaData);
_param1Fact->_setName("Hold:"); _param1Fact->_setName("Hold:");
_param1Fact->setMetaData(_holdTimeMetaData); _param1Fact->setMetaData(_holdTimeMetaData);
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
model->append(_param2Fact); model->append(_param2Fact);
model->append(_param1Fact); model->append(_param1Fact);
break; break;
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
model->append(_loiterOrbitRadiusFact); model->append(_loiterOrbitRadiusFact);
break; break;
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
_param1Fact->_setName("Turns:"); _param1Fact->_setName("Turns:");
_param1Fact->setMetaData(_loiterTurnsMetaData); _param1Fact->setMetaData(_loiterTurnsMetaData);
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
model->append(_loiterOrbitRadiusFact); model->append(_loiterOrbitRadiusFact);
model->append(_param1Fact); model->append(_param1Fact);
...@@ -607,18 +646,25 @@ QmlObjectListModel* MissionItem::facts(void) ...@@ -607,18 +646,25 @@ QmlObjectListModel* MissionItem::facts(void)
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
_param1Fact->_setName("Seconds:"); _param1Fact->_setName("Seconds:");
_param1Fact->setMetaData(_loiterSecondsMetaData); _param1Fact->setMetaData(_loiterSecondsMetaData);
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
model->append(_loiterOrbitRadiusFact); model->append(_loiterOrbitRadiusFact);
model->append(_param1Fact); model->append(_param1Fact);
break; break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
break;
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
break; break;
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
_param1Fact->_setName("Pitch:"); _param1Fact->_setName("Pitch:");
_param1Fact->setMetaData(_pitchMetaData); _param1Fact->setMetaData(_pitchMetaData);
model->append(_latitudeFact);
model->append(_longitudeFact);
model->append(_altitudeFact);
model->append(_yawRadiansFact); model->append(_yawRadiansFact);
model->append(_param1Fact); model->append(_param1Fact);
break; break;
...@@ -642,30 +688,36 @@ QmlObjectListModel* MissionItem::facts(void) ...@@ -642,30 +688,36 @@ QmlObjectListModel* MissionItem::facts(void)
return model; return model;
} }
int MissionItem::factCount(void) QmlObjectListModel* MissionItem::checkboxFacts(void)
{ {
QmlObjectListModel* model = new QmlObjectListModel(this);
switch ((MAV_CMD)_command) { switch ((MAV_CMD)_command) {
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
return 3; model->append(_altitudeRelativeToHomeFact);
break;
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
return 2; model->append(_altitudeRelativeToHomeFact);
break;
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
return 3; model->append(_altitudeRelativeToHomeFact);
break;
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
return 3; model->append(_altitudeRelativeToHomeFact);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return 0; break;
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
return 1; model->append(_altitudeRelativeToHomeFact);
break;
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
return 2; model->append(_altitudeRelativeToHomeFact);
case MAV_CMD_CONDITION_DELAY: break;
return 1;
case MAV_CMD_DO_JUMP:
return 2;
default: default:
return 0; break;
} }
return model;
} }
double MissionItem::yawRadians(void) const double MissionItem::yawRadians(void) const
...@@ -695,3 +747,14 @@ void MissionItem::setYawDegrees(double yaw) ...@@ -695,3 +747,14 @@ void MissionItem::setYawDegrees(double yaw)
setYawRadians(yaw * (M_PI / 180.0)); setYawRadians(yaw * (M_PI / 180.0));
} }
QGeoCoordinate MissionItem::coordinate(void) const
{
return QGeoCoordinate(latitude(), longitude(), altitude());
}
void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
setLatitude(coordinate.latitude());
setLongitude(coordinate.longitude());
setAltitude(coordinate.altitude());
}
...@@ -60,7 +60,7 @@ public: ...@@ -60,7 +60,7 @@ public:
Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged) Q_PROPERTY(int sequenceNumber READ sequenceNumber WRITE setSequenceNumber NOTIFY sequenceNumberChanged)
Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged) Q_PROPERTY(bool isCurrentItem READ isCurrentItem WRITE setIsCurrentItem NOTIFY isCurrentItemChanged)
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY specifiesCoordinateChanged) Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate NOTIFY commandChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(double yaw READ yawDegrees WRITE setYawDegrees NOTIFY yawChanged) Q_PROPERTY(double yaw READ yawDegrees WRITE setYawDegrees NOTIFY yawChanged)
Q_PROPERTY(QStringList commandNames READ commandNames CONSTANT) Q_PROPERTY(QStringList commandNames READ commandNames CONSTANT)
...@@ -68,8 +68,8 @@ public: ...@@ -68,8 +68,8 @@ public:
Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged) Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged)
Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged) Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged) Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged)
Q_PROPERTY(QmlObjectListModel* facts READ facts NOTIFY commandChanged) Q_PROPERTY(QmlObjectListModel* textFieldFacts READ textFieldFacts NOTIFY commandChanged)
Q_PROPERTY(int factCount READ factCount 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(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
// Property accesors // Property accesors
...@@ -82,7 +82,7 @@ public: ...@@ -82,7 +82,7 @@ public:
bool specifiesCoordinate(void) const; bool specifiesCoordinate(void) const;
QGeoCoordinate coordinate(void) const { return _coordinate; } QGeoCoordinate coordinate(void) const;
void setCoordinate(const QGeoCoordinate& coordinate); void setCoordinate(const QGeoCoordinate& coordinate);
QStringList commandNames(void); QStringList commandNames(void);
...@@ -97,17 +97,17 @@ public: ...@@ -97,17 +97,17 @@ public:
QStringList valueLabels(void); QStringList valueLabels(void);
QStringList valueStrings(void); QStringList valueStrings(void);
QmlObjectListModel* facts(void); QmlObjectListModel* textFieldFacts(void);
int factCount(void); QmlObjectListModel* checkboxFacts(void);
double yawDegrees(void) const; double yawDegrees(void) const;
void setYawDegrees(double yaw); void setYawDegrees(double yaw);
// C++ only methods // C++ only methods
double latitude(void) const { return _coordinate.latitude(); } double latitude(void) const { return _latitudeFact->value().toDouble(); }
double longitude(void) const { return _coordinate.longitude(); } double longitude(void) const { return _longitudeFact->value().toDouble(); }
double altitude(void) const { return _coordinate.altitude(); } double altitude(void) const { return _altitudeFact->value().toDouble(); }
void setLatitude(double latitude); void setLatitude(double latitude);
void setLongitude(double longitude); void setLongitude(double longitude);
...@@ -158,9 +158,8 @@ public: ...@@ -158,9 +158,8 @@ public:
return altitude(); return altitude();
} }
// MAV_FRAME // MAV_FRAME
int frame() const { int frame() const;
return _frame;
}
// MAV_CMD // MAV_CMD
int command() const { int command() const {
return _command; return _command;
...@@ -176,7 +175,6 @@ public: ...@@ -176,7 +175,6 @@ public:
signals: signals:
void sequenceNumberChanged(int sequenceNumber); void sequenceNumberChanged(int sequenceNumber);
void specifiesCoordinateChanged(bool specifiesCoordinate);
void isCurrentItemChanged(bool isCurrentItem); void isCurrentItemChanged(bool isCurrentItem);
void coordinateChanged(const QGeoCoordinate& coordinate); void coordinateChanged(const QGeoCoordinate& coordinate);
void yawChanged(double yaw); void yawChanged(double yaw);
...@@ -226,17 +224,20 @@ private: ...@@ -226,17 +224,20 @@ private:
} MavCmd2Name_t; } MavCmd2Name_t;
int _sequenceNumber; int _sequenceNumber;
QGeoCoordinate _coordinate;
int _frame; int _frame;
MavlinkQmlSingleton::Qml_MAV_CMD _command; MavlinkQmlSingleton::Qml_MAV_CMD _command;
bool _autocontinue; bool _autocontinue;
bool _isCurrentItem; bool _isCurrentItem;
quint64 _reachedTime; quint64 _reachedTime;
Fact* _latitudeFact;
Fact* _longitudeFact;
Fact* _altitudeFact;
Fact* _yawRadiansFact; Fact* _yawRadiansFact;
Fact* _loiterOrbitRadiusFact; Fact* _loiterOrbitRadiusFact;
Fact* _param1Fact; Fact* _param1Fact;
Fact* _param2Fact; Fact* _param2Fact;
Fact* _altitudeRelativeToHomeFact;
FactMetaData* _pitchMetaData; FactMetaData* _pitchMetaData;
FactMetaData* _acceptanceRadiusMetaData; FactMetaData* _acceptanceRadiusMetaData;
...@@ -251,4 +252,7 @@ private: ...@@ -251,4 +252,7 @@ private:
static const MavCmd2Name_t _rgMavCmd2Name[_cMavCmd2Name]; static const MavCmd2Name_t _rgMavCmd2Name[_cMavCmd2Name];
}; };
QDebug operator<<(QDebug dbg, const MissionItem& missionItem);
QDebug operator<<(QDebug dbg, const MissionItem* missionItem);
#endif #endif
...@@ -20,13 +20,14 @@ Rectangle { ...@@ -20,13 +20,14 @@ Rectangle {
signal moveUp signal moveUp
signal moveDown signal moveDown
// FIXME: THis doesn't work right for RTL
height: missionItem.isCurrentItem ? height: missionItem.isCurrentItem ?
((missionItem.factCount + (missionItem.specifiesCoordinate ? 3 : 0)) * (latitudeField.height + _margin)) + commandPicker.height + deleteButton.height + (_margin * 6) : (missionItem.textFieldFacts.count * (measureTextField.height + _margin)) +
(missionItem.checkboxFacts.count * (measureCheckbox.height + _margin)) +
commandPicker.height + deleteButton.height + (_margin * 9) :
commandPicker.height + (_margin * 2) commandPicker.height + (_margin * 2)
color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 13 readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 16
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 3 readonly property real _margin: ScreenTools.defaultFontPixelWidth / 3
QGCPalette { QGCPalette {
...@@ -34,6 +35,16 @@ Rectangle { ...@@ -34,6 +35,16 @@ Rectangle {
colorGroupEnabled: enabled colorGroupEnabled: enabled
} }
QGCTextField {
id: measureTextField
visible: false
}
QGCCheckBox {
id: measureCheckbox
visible: false
}
Item { Item {
anchors.margins: _margin anchors.margins: _margin
anchors.fill: parent anchors.fill: parent
...@@ -65,7 +76,7 @@ Rectangle { ...@@ -65,7 +76,7 @@ Rectangle {
} }
Rectangle { Rectangle {
anchors.margins: _margin anchors.topMargin: _margin
anchors.top: commandPicker.bottom anchors.top: commandPicker.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
anchors.left: parent.left anchors.left: parent.left
...@@ -77,76 +88,18 @@ Rectangle { ...@@ -77,76 +88,18 @@ Rectangle {
anchors.margins: _margin anchors.margins: _margin
anchors.fill: parent anchors.fill: parent
QGCTextField {
id: latitudeField
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.latitude
visible: missionItem.specifiesCoordinate
onAccepted: missionItem.coordinate.latitude = text
}
QGCTextField {
id: longitudeField
anchors.topMargin: _margin
anchors.top: latitudeField.bottom
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.longitude
visible: missionItem.specifiesCoordinate
onAccepted: missionItem.coordinate.longtitude = text
}
QGCTextField {
id: altitudeField
anchors.topMargin: _margin
anchors.top: longitudeField.bottom
anchors.right: parent.right
width: _editFieldWidth
text: missionItem.coordinate.altitude
visible: missionItem.specifiesCoordinate
showUnits: true
unitsLabel: "meters"
onAccepted: missionItem.coordinate.altitude = text
}
QGCLabel {
anchors.left: parent.left
anchors.baseline: latitudeField.baseline
text: "Lat:"
visible: missionItem.specifiesCoordinate
}
QGCLabel {
anchors.left: parent.left
anchors.baseline: longitudeField.baseline
text: "Long:"
visible: missionItem.specifiesCoordinate
}
QGCLabel {
anchors.left: parent.left
anchors.baseline: altitudeField.baseline
text: "Alt:"
visible: missionItem.specifiesCoordinate
}
Column { Column {
id: valueColumn id: valuesColumn
anchors.topMargin: _margin anchors.left: parent.left
anchors.left: parent.left anchors.right: parent.right
anchors.right: parent.right anchors.top: parent.top
anchors.top: missionItem.specifiesCoordinate ? altitudeField.bottom : parent.top spacing: _margin
spacing: _margin
Repeater { Repeater {
model: missionItem.facts model: missionItem.textFieldFacts
Item { Item {
width: valueColumn.width width: valuesColumn.width
height: textField.height height: textField.height
QGCLabel { QGCLabel {
...@@ -163,39 +116,57 @@ Rectangle { ...@@ -163,39 +116,57 @@ Rectangle {
} }
} }
} }
} // Column - Values column
Row {
anchors.topMargin: _margin
anchors.top: valueColumn.bottom
width: parent.width Item {
spacing: _margin width: 10
height: missionItem.textFieldFacts.count ? _margin : 0
}
readonly property real buttonWidth: (width - (_margin * 2)) / 3 Repeater {
model: missionItem.checkboxFacts
QGCButton { FactCheckBox {
id: deleteButton id: textField
width: parent.buttonWidth text: object.name
text: "Delete" fact: object
}
}
onClicked: _root.remove() Item {
width: 10
height: missionItem.checkboxFacts.count ? _margin : 0
} }
QGCButton { Row {
width: parent.buttonWidth width: parent.width
text: "Up" spacing: _margin
onClicked: _root.moveUp() readonly property real buttonWidth: (width - (_margin * 2)) / 3
}
QGCButton {
id: deleteButton
width: parent.buttonWidth
text: "Delete"
onClicked: _root.remove()
}
QGCButton { QGCButton {
width: parent.buttonWidth width: parent.buttonWidth
text: "Down" text: "Up"
onClicked: _root.moveDown() onClicked: _root.moveUp()
}
QGCButton {
width: parent.buttonWidth
text: "Down"
onClicked: _root.moveDown()
}
} }
}
} // Column
} // Item } // Item
} // Rectangle } // Rectangle
} // Item } // Item
......
...@@ -117,7 +117,6 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p ...@@ -117,7 +117,6 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p
//_objectList[position]->deleteLater(); //_objectList[position]->deleteLater();
_objectList.removeAt(position); _objectList.removeAt(position);
} }
qDebug() << _objectList;
endRemoveRows(); endRemoveRows();
emit countChanged(count()); emit countChanged(count());
......
...@@ -46,6 +46,13 @@ public: ...@@ -46,6 +46,13 @@ public:
QObject* operator[](int i); QObject* operator[](int i);
const QObject* operator[](int i) const; const QObject* operator[](int i) const;
template <class T>
const QList<T*>& list(void) { return *((QList<T*>*)((void*)(&_objectList))); }
signals:
void countChanged(int count);
private:
// Overrides from QAbstractListModel // Overrides from QAbstractListModel
virtual int rowCount(const QModelIndex & parent = QModelIndex()) const; virtual int rowCount(const QModelIndex & parent = QModelIndex()) const;
virtual QVariant data(const QModelIndex & index, int role = Qt::DisplayRole) const; virtual QVariant data(const QModelIndex & index, int role = Qt::DisplayRole) const;
...@@ -53,9 +60,6 @@ public: ...@@ -53,9 +60,6 @@ public:
virtual bool insertRows(int position, int rows, const QModelIndex &index = QModelIndex()); virtual bool insertRows(int position, int rows, const QModelIndex &index = QModelIndex());
virtual bool removeRows(int position, int rows, const QModelIndex &index = QModelIndex()); virtual bool removeRows(int position, int rows, const QModelIndex &index = QModelIndex());
virtual bool setData(const QModelIndex &index, const QVariant &value, int role = Qt::EditRole); virtual bool setData(const QModelIndex &index, const QVariant &value, int role = Qt::EditRole);
signals:
void countChanged(int count);
private: private:
QList<QObject*> _objectList; QList<QObject*> _objectList;
......
...@@ -936,5 +936,9 @@ void Vehicle::setActive(bool active) ...@@ -936,5 +936,9 @@ void Vehicle::setActive(bool active)
QmlObjectListModel* Vehicle::missionItemsModel(void) QmlObjectListModel* Vehicle::missionItemsModel(void)
{ {
return &_missionItems; if (qgcApp()->useNewMissionEditor()) {
return missionManager()->missionItems();
} else {
return &_missionItems;
}
} }
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment