Newer
Older
/*=====================================================================
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 <QTextStream>
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(MissionItemLog)
MissionItem(QObject *parent = 0,
int sequenceNumber = 0,
QGeoCoordinate coordiante = QGeoCoordinate(),
double param1 = 0.0,
double param2 = 0.0,
double param3 = 0.0,
double param4 = 0.0,
bool autocontinue = true,
bool isCurrentItem = false,
MissionItem(const MissionItem& other, QObject* parent = NULL);
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(QStringList commandNames READ commandNames CONSTANT)
Q_PROPERTY(QString commandName READ commandName 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)
// Property accesors
int sequenceNumber(void) const { return _sequenceNumber; }
void setSequenceNumber(int sequenceNumber);
bool isCurrentItem(void) const { return _isCurrentItem; }
void setIsCurrentItem(bool isCurrentItem);
void setCoordinate(const QGeoCoordinate& coordinate);
QStringList commandNames(void);
QString commandName(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);
double yawDegrees(void) const;
void setYawDegrees(double yaw);
bool dirty(void) { return _dirty; }
void setDirty(bool dirty);
/// 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);
double yawRadians(void) const;
void setYawRadians(double yaw);
double loiterOrbitRadius() const {
return _loiterOrbitRadiusFact->value().toDouble();
double acceptanceRadius() const {
return param2();
/** @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);
signals:
void sequenceNumberChanged(int sequenceNumber);
void isCurrentItemChanged(bool isCurrentItem);
void coordinateChanged(const QGeoCoordinate& coordinate);
/** @brief Announces a change to the waypoint data */
void changed(MissionItem* wp);
void commandNameChanged(QString type);
void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void valueLabelsChanged(QStringList valueLabels);
void valueStringsChanged(QStringList valueStrings);
/** @brief Set the waypoint action */
void setAction (int _action);
void setFrame (int _frame);
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);
void setReached () { _reachedTime = QGC::groundTimeMilliseconds(); }
bool isReached () { return (_reachedTime > 0); }
void setChanged() {
emit changed(this);
}
private slots:
void _factValueChanged(QVariant value);
void _coordinateFactChanged(QVariant value);
private:
QString _oneDecimalString(double value);
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;
Fact* _latitudeFact;
Fact* _longitudeFact;
Fact* _altitudeFact;
Fact* _yawRadiansFact;
Fact* _loiterOrbitRadiusFact;
FactMetaData* _pitchMetaData;
FactMetaData* _acceptanceRadiusMetaData;
FactMetaData* _holdTimeMetaData;
FactMetaData* _loiterTurnsMetaData;
FactMetaData* _loiterSecondsMetaData;
FactMetaData* _delaySecondsMetaData;
FactMetaData* _jumpSequenceMetaData;
FactMetaData* _jumpRepeatMetaData;
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);