Commit a6776c0a authored by Valentin Platzgummer's avatar Valentin Platzgummer

flight view edited

parent 175e7c28
This source diff could not be displayed because it is too large. You can view the blob instead.
......@@ -528,26 +528,6 @@ QGCView {
FlightDisplayViewWidgets {
id: flightDisplayViewWidgets
z: _panel.z + 4
<<<<<<< HEAD
height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0) - wimaMenu.height
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.top: singleMultiSelector.bottom
qgcView: root
useLightColors: isBackgroundDark
missionController: _missionController
visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
}
FlightDisplayWimaMenu {
id: wimaMenu
z: 1000 //_panel.z + 4
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
anchors.top: flightDisplayViewWidgets.bottom
visible: true
height: 300
width: 200
=======
height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
anchors.left: parent.left
anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
......@@ -568,7 +548,6 @@ QGCView {
wimaController: wimaController
>>>>>>> bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
//-------------------------------------------------------------------------
......
......@@ -19,15 +19,9 @@ import QGroundControl.FactControls 1.0
Item {
id: _root
height: 400
width: 250
<<<<<<< HEAD
Text {
id: enableWima
text: qsTr("WiMA")
font.pointSize: 40
=======
height: 500
width: 300
property var wimaController // must be provided by the user
// box containing all items
......@@ -161,8 +155,5 @@ Item {
}
}
}
>>>>>>> bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
}
......@@ -1053,6 +1053,31 @@ bool MissionController::readyForSaveSend(void) const
return true;
}
bool MissionController::setTakeoffCommand(SimpleMissionItem &missionItem, Vehicle &vehicle)
{
if (vehicle.fixedWing() || vehicle.vtol() || vehicle.multiRotor()) {
MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
missionItem.setCommand(takeoffCmd);
}
}
else
return false;
return true;
}
bool MissionController::setLandCommand(SimpleMissionItem &missionItem, Vehicle &vehicle)
{
MAV_CMD landCmd = vehicle.vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (vehicle.firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
missionItem.setCommand(landCmd);
} else
return false;
return true;
}
void MissionController::save(QJsonObject& json)
{
json[JsonHelper::jsonVersionKey] = _missionFileVersion;
......
......@@ -150,12 +150,18 @@ public:
/// would return false is when it is still waiting on terrain data to determine correct altitudes.
bool readyForSaveSend(void) const;
/// sets the command in missionItem to a land command
bool setLandCommand (SimpleMissionItem &missionItem, Vehicle &vehicle);
/// sets the command in missionItem to a takeoff command
bool setTakeoffCommand (SimpleMissionItem &missionItem, Vehicle &vehicle);
/// Sends the mission items to the specified vehicle
static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
static bool convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent);
bool loadJsonFile(QFile& file, QString& errorString);
bool loadTextFile(QFile& file, QString& errorString);
......
......@@ -26,6 +26,11 @@ QVariantList WimaAreaData::path() const
return _path;
}
QGeoCoordinate WimaAreaData::center() const
{
return _center;
}
QList<QGeoCoordinate> WimaAreaData::coordinateList() const
{
QList<QGeoCoordinate> coordinateList;
......@@ -57,6 +62,15 @@ void WimaAreaData::setPath(const QVariantList &coordinateList)
_path.append(coordinateList);
}
void WimaAreaData::setCenter(const QGeoCoordinate &center)
{
if (_center != center) {
_center = center;
emit centerChanged();
}
}
/*!
* \fn void WimaAreaData::assign(const WimaAreaData &other)
*
......@@ -66,12 +80,14 @@ void WimaAreaData::assign(const WimaAreaData &other)
{
setMaxAltitude(other.maxAltitude());
setPath(other.path());
setCenter(other.center());
}
void WimaAreaData::assign(const WimaArea &other)
{
setMaxAltitude(other.maxAltitude());
setPath(other.path());
setPath(other.path());
setCenter(other.center());
}
......
......@@ -19,9 +19,10 @@ public:
//WimaAreaData(const WimaArea &other, QObject *parent = nullptr);
WimaAreaData& operator=(const WimaAreaData& otherData) = delete; // avoid slicing
double maxAltitude() const;
QVariantList path() const;
QList<QGeoCoordinate> coordinateList() const;
double maxAltitude() const;
QVariantList path() const;
QGeoCoordinate center() const;
QList<QGeoCoordinate> coordinateList() const;
virtual QString type() const = 0;
......@@ -29,11 +30,13 @@ public:
signals:
void maxAltitudeChanged (double maxAltitude);
void pathChanged (const QVariantList& coordinateList);
void centerChanged (void);
public slots:
void setMaxAltitude(double maxAltitude);
void setPath(const QList<QGeoCoordinate> &coordinateList);
void setPath(const QVariantList &coordinateList);
void setPath(const QVariantList &coordinateList);
void setCenter(const QGeoCoordinate &center);
protected:
void assign(const WimaAreaData &other);
......@@ -46,5 +49,6 @@ private:
// see WimaArea.h for explanation
double _maxAltitude;
QVariantList _path;
QGeoCoordinate _center;
};
......@@ -13,14 +13,16 @@
},
{
"name": "MaxWaypointsPerPhase",
"shortDescription": "Determines the maximum number of waypoints per phase.",
"shortDescription": "Determines the maximum number of waypoints per phase. This number does not include the arrival and return path.",
"type": "uint32",
"min" : 1,
"defaultValue": 30
},
{
"name": "StartWaypointIndex",
"shortDescription": "The index of the start waypoint for the next mission phase.",
"type": "uint32",
"type": "uint32",
"min" : 1,
"defaultValue": 1
},
{
......
This diff is collapsed.
......@@ -85,12 +85,8 @@ public:
Q_INVOKABLE void nextPhase();
Q_INVOKABLE void previousPhase();
Q_INVOKABLE void resetPhase();
Q_INVOKABLE void uploadToVehicle();
Q_INVOKABLE bool uploadToVehicle();
Q_INVOKABLE void removeFromVehicle();
Q_INVOKABLE void startMission();
Q_INVOKABLE void abortMission();
Q_INVOKABLE void pauseMission();
Q_INVOKABLE void resumeMission();
Q_INVOKABLE void saveToCurrent ();
Q_INVOKABLE void saveToFile (const QString& filename);
......@@ -137,12 +133,13 @@ signals:
void currentWaypointPathChanged (void);
private slots:
void fetchContainerData (bool valid);
void calcNextPhase (void);
bool fetchContainerData();
bool calcNextPhase(void);
void updateWaypointPath (void);
void updateCurrentPath (void);
void updateNextWaypoint (void);
void recalcCurrentPhase (void);
bool setTakeoffLandPosition(void);
private:
......@@ -161,8 +158,6 @@ private:
// _currentMissionItems contains a number of mission items which can be worked off with a single battery chrage
QVariantList _waypointPath; // path connecting the items in _missionItems
QVariantList _currentWaypointPath; // path connecting the items in _currentMissionItems
QList<int> _startWaypointIndexList; // list containing the last start waypoint indices, used by previosPhase
QGeoCoordinate _takeoffLandPostion;
......@@ -170,7 +165,7 @@ private:
SettingsFact _enableWimaController; // enables or disables the wimaControler
SettingsFact _overlapWaypoints; // determines the number of overlapping waypoints between two consecutive mission phases
SettingsFact _maxWaypointsPerPhase; // determines the maximum number waypoints per phase
SettingsFact _nestPhaseStartWaypointIndex; // index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
SettingsFact _nextPhaseStartWaypointIndex; // index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
// defining the first element of the next phase
SettingsFact _showAllMissionItems; // bool value, Determines whether the mission items of the overall mission are displayed or not.
SettingsFact _showCurrentMissionItems; // bool value, Determines whether the mission items of the current mission phase are displayed or not.
......@@ -179,4 +174,5 @@ private:
// (which is not part of the return path) of _currentMissionItem
int _startWaypointIndex; // indes of the mission item stored in _missionItems defining the first element
// (which is not part of the arrival path) of _currentMissionItem
bool _lastMissionPhaseReached;
};
......@@ -3,29 +3,10 @@
WimaDataContainer::WimaDataContainer(QObject *parent)
: QObject (parent)
, _planData (this /* parent */)
, _dataValid (false)
{
}
/*!
* \fn bool WimaDataContainer::dataValid() const
* Returns \c true if the data is valid, \c false else.
*/
bool WimaDataContainer::dataValid() const/*!
* \fn bool dijkstraAlgorithm(int startIndex, int endIndex, const QList<T> elements, QList<T> &elementPath, double(*distance)(const T &t1, const T &t2))
* Calculates the shortest path between the elements stored in \a elements.
* The \l {Dijkstra Algorithm} is used to find the shorest path.
* Stores the result inside \a elementPath when sucessfull.
* The function handle \a distance is used to calculate the distance between two elements. The distance must be positive.
* Returns \c true if successful, \c false else.
*
* \sa QList
*/
{
return _dataValid;
}
/*!
* \fn void WimaDataContainer::push(const WimaPlanData &planData)
*
......@@ -36,9 +17,9 @@ bool WimaDataContainer::dataValid() const/*!
*/
void WimaDataContainer::push(const WimaPlanData &planData)
{
setDataValid(false);
_planData = planData;
setDataValid(true);
emit newDataAvailable();
}
/*!
......@@ -53,23 +34,6 @@ const WimaPlanData &WimaDataContainer::pull() const
return _planData;
}
/*!
* \fn void WimaDataContainer::setDataValid(bool valid)
*
* Sets the validity of the data to \a valid.
* Mainly for internal usage. Should be invoked from \c WimaPlaner only.
*
* \sa WimaPlanData
*/
void WimaDataContainer::setDataValid(bool valid)
{
if ( _dataValid != valid ) {
_dataValid = valid;
emit dataValidChanged(_dataValid);
}
}
/*!
* \class WimaDataContainer
* \brief Data container designed for data exchange between \c WimaPlaner and \c WimaController.
......
......@@ -17,16 +17,14 @@ public:
bool dataValid() const;
signals:
void dataValidChanged (bool valid);
void newDataAvailable(void);
public slots:
void push(const WimaPlanData &planData);
const WimaPlanData &pull() const;
void setDataValid(bool valid);
private:
WimaPlanData _planData;
bool _dataValid;
};
......@@ -73,11 +73,11 @@ void WimaPlaner::setDataContainer(WimaDataContainer *container)
{
if (container != nullptr) {
if (_container != nullptr) {
disconnect(this, &WimaPlaner::missionReadyChanged, _container, &WimaDataContainer::setDataValid);
disconnect(this, &WimaPlaner::missionReadyChanged, _container, &WimaDataContainer::newDataAvailable);
}
_container = container;
connect(this, &WimaPlaner::missionReadyChanged, _container, &WimaDataContainer::setDataValid);
connect(this, &WimaPlaner::missionReadyChanged, _container, &WimaDataContainer::newDataAvailable);
emit dataContainerChanged();
}
......@@ -178,32 +178,9 @@ void WimaPlaner::removeAll()
emit visualItemsChanged();
}
void WimaPlaner::startMission()
{
}
void WimaPlaner::abortMission()
{
}
void WimaPlaner::pauseMission()
{
}
void WimaPlaner::resumeMission()
{
}
bool WimaPlaner::updateMission()
{
#if TEST_FUN
TestPlanimetryCalculus::test();
TestPolygonCalculus::test();
#endif
QString errorString;
setMissionReady(false);
#define debug 0
......@@ -306,11 +283,7 @@ bool WimaPlaner::updateMission()
qgcApp()->showMessage( QString(tr("Not able to calculate the path from takeoff position to measurement area.")).toLocal8Bit().data());
return false;
}
// path.clear();
// path.append(end);
// path.append(start);
// path.append(end);
// path.append(end);
_arrivalPathLength = path.size()-1; // -1: last item is first measurement point
for (int i = 1; i < path.count()-1; i++) {
sequenceNumber = _missionController->insertSimpleMissionItem(path.value(i), missionItems->count()-1);
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
......@@ -324,7 +297,7 @@ bool WimaPlaner::updateMission()
qgcApp()->showMessage(QString(tr("Not able to calculate the path from measurement area to landing position.")).toLocal8Bit().data());
return false;
}
_returnPathLength = path.size()-1; // -1: fist item is last measurement point
for (int i = 1; i < path.count()-1; i++) {
sequenceNumber = _missionController->insertSimpleMissionItem(path.value(i), missionItems->count());
_missionController->setCurrentPlanViewIndex(sequenceNumber, true);
......@@ -338,13 +311,8 @@ bool WimaPlaner::updateMission()
qWarning("WimaPlaner::updateMission(): landItem == nullptr");
return false;
} else {
Vehicle* controllerVehicle = _masterController->controllerVehicle();
MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
landItem->setCommand(landCmd);
} else {
if (!_missionController->setLandCommand(*landItem, *_masterController->controllerVehicle()))
return false;
}
}
pushToContainer(); // exchange plan data with the WimaController via the _container
......@@ -662,23 +630,12 @@ WimaPlanData WimaPlaner::toPlanData()
QList<MissionItem*> rgMissionItems;
MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, this);
// remove warnings if you read this
// qWarning("WimaPlaner::toPlanData(): rgMissionItems");
// for (auto item : rgMissionItems) {
// qWarning() << item->command();
// qWarning() << item->param1();
// qWarning() << item->param2();
// qWarning() << item->param3();
// qWarning() << item->param4();
// qWarning() << item->param5();
// qWarning() << item->param6();
// qWarning() << item->param7();
// qWarning(" ");
// }
// add const qualifier...
QList<const MissionItem*> rgMissionItemsConst;
for (auto missionItem : rgMissionItems)
rgMissionItemsConst.append(missionItem);
for (int i = _arrivalPathLength + 1; i < rgMissionItems.size() - _returnPathLength; i++) { // i = _arrivalPathLength + 1: + 1 = MissionSettingsItem ...
rgMissionItemsConst.append(rgMissionItems.value(i));
}
// store mavlink commands
planData.append(rgMissionItemsConst);
......
......@@ -91,11 +91,6 @@ public:
Q_INVOKABLE bool addCorridor();
/// Remove all areas from WimaPlaner and all mission items from MissionController
Q_INVOKABLE void removeAll();
Q_INVOKABLE void startMission();
Q_INVOKABLE void abortMission();
Q_INVOKABLE void pauseMission();
Q_INVOKABLE void resumeMission();
/// Recalculates vehicle corridor, flight path, etc.
Q_INVOKABLE bool updateMission();
......@@ -147,4 +142,6 @@ private:
WimaMeasurementArea _measurementArea; // measurement area
WimaServiceArea _serviceArea; // area for supplying
WimaCorridor _corridor; // corridor connecting _measurementArea and _serviceArea
int _arrivalPathLength; // the number waypoints the arrival path consists of (path from takeoff to first measurement point)
int _returnPathLength; // the number waypoints the return path consists of (path from last measurement point to land)
};
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