MissionSettingsItem.cc 10.2 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#include "MissionSettingsItem.h"
11 12 13 14 15 16 17
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include "SimpleMissionItem.h"
#include "SettingsManager.h"
#include "AppSettings.h"
18
#include "MissionCommandUIInfo.h"
19 20 21 22 23

#include <QPolygonF>

QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")

24
const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings";
25

DonLakeFlyer's avatar
DonLakeFlyer committed
26
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
27

28
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
29

30
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
31
    : ComplexMissionItem                (vehicle, parent)
32
    , _plannedHomePositionAltitudeFact  (0, _plannedHomePositionAltitudeName,   FactMetaData::valueTypeDouble)
33 34 35 36 37
    , _missionEndRTL                    (false)
    , _cameraSection                    (vehicle)
    , _speedSection                     (vehicle)
    , _sequenceNumber                   (0)
    , _dirty                            (false)
38 39 40 41 42 43 44 45 46 47 48 49 50
{
    _editorQml = "qrc:/qml/MissionSettingsEditor.qml";

    if (_metaDataMap.isEmpty()) {
        _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */);
    }

    _plannedHomePositionAltitudeFact.setMetaData    (_metaDataMap[_plannedHomePositionAltitudeName]);

    _plannedHomePositionAltitudeFact.setRawValue    (_plannedHomePositionAltitudeFact.rawDefaultValue());

    setHomePositionSpecialCase(true);

51
    connect(this,               &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
52
    connect(this,               &MissionSettingsItem::missionEndRTLChanged,             this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
53 54
    connect(&_cameraSection,    &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
    connect(&_speedSection,     &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
55

56
    connect(&_plannedHomePositionAltitudeFact,  &Fact::valueChanged,                        this, &MissionSettingsItem::_setDirty);
57

58
    connect(&_plannedHomePositionAltitudeFact,  &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate);
59

60 61
    connect(&_cameraSection,    &CameraSection::dirtyChanged,   this, &MissionSettingsItem::_sectionDirtyChanged);
    connect(&_speedSection,     &SpeedSection::dirtyChanged,    this, &MissionSettingsItem::_sectionDirtyChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
62

63 64
    connect(&_cameraSection,    &CameraSection::specifyGimbalChanged,       this, &MissionSettingsItem::specifiedGimbalYawChanged);
    connect(&_cameraSection,    &CameraSection::specifiedGimbalYawChanged,  this, &MissionSettingsItem::specifiedGimbalYawChanged);
65 66 67
}


68
int MissionSettingsItem::lastSequenceNumber(void) const
69
{
70
    int lastSequenceNumber = _sequenceNumber;
71

72 73
    lastSequenceNumber += _cameraSection.itemCount();
    lastSequenceNumber += _speedSection.itemCount();
74 75 76 77

    return lastSequenceNumber;
}

78
void MissionSettingsItem::setDirty(bool dirty)
79 80 81 82 83 84 85
{
    if (_dirty != dirty) {
        _dirty = dirty;
        emit dirtyChanged(_dirty);
    }
}

86
void MissionSettingsItem::save(QJsonArray&  missionItems)
87
{
88 89 90
    QList<MissionItem*> items;

    appendMissionItems(items, this);
91 92

    // First item show be planned home position, we are not reponsible for save/load
93
    // Remaining items we just output as is
94 95
    for (int i=1; i<items.count(); i++) {
        MissionItem* item = items[i];
96 97 98
        QJsonObject saveObject;
        item->save(saveObject);
        missionItems.append(saveObject);
99
        item->deleteLater();
100 101 102
    }
}

103
void MissionSettingsItem::setSequenceNumber(int sequenceNumber)
104 105 106 107 108 109 110 111
{
    if (_sequenceNumber != sequenceNumber) {
        _sequenceNumber = sequenceNumber;
        emit sequenceNumberChanged(sequenceNumber);
        emit lastSequenceNumberChanged(lastSequenceNumber());
    }
}

112
bool MissionSettingsItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
113 114 115 116 117 118 119 120
{
    Q_UNUSED(complexObject);
    Q_UNUSED(sequenceNumber);
    Q_UNUSED(errorString);

    return true;
}

121
double MissionSettingsItem::greatestDistanceTo(const QGeoCoordinate &other) const
122 123 124 125 126
{
    Q_UNUSED(other);
    return 0;
}

127
bool MissionSettingsItem::specifiesCoordinate(void) const
128
{
DonLakeFlyer's avatar
DonLakeFlyer committed
129
    return true;
130 131
}

132
void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
133 134 135
{
    int seqNum = _sequenceNumber;

136
    // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
137 138 139 140 141 142 143 144 145

    // Planned home position
    MissionItem* item = new MissionItem(seqNum++,
                                        MAV_CMD_NAV_WAYPOINT,
                                        MAV_FRAME_GLOBAL,
                                        0,                      // Hold time
                                        0,                      // Acceptance radius
                                        0,                      // Not sure?
                                        0,                      // Yaw
146 147
                                        coordinate().latitude(),
                                        coordinate().longitude(),
148 149 150
                                        _plannedHomePositionAltitudeFact.rawValue().toDouble(),
                                        true,                   // autoContinue
                                        false,                  // isCurrentItem
151 152
                                        missionItemParent);
    items.append(item);
153

154 155
    _cameraSection.appendSectionItems(items, missionItemParent, seqNum);
    _speedSection.appendSectionItems(items, missionItemParent, seqNum);
156 157
}

158
bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int seqNum, QObject* missionItemParent)
159 160 161
{
    MissionItem* item = NULL;

162
    // IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
163

164
    if (_missionEndRTL) {
165 166 167 168 169 170 171 172 173 174 175 176 177 178 179
        qCDebug(MissionSettingsComplexItemLog) << "Appending end action RTL seqNum" << seqNum;
        item = new MissionItem(seqNum,
                               MAV_CMD_NAV_RETURN_TO_LAUNCH,
                               MAV_FRAME_MISSION,
                               0, 0, 0, 0, 0, 0, 0,        // param 1-7 not used
                               true,                       // autoContinue
                               false,                      // isCurrentItem
                               missionItemParent);
        items.append(item);
        return true;
    } else {
        return false;
    }
}

180
bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex)
181
{
182
    bool foundSpeedSection = false;
183 184
    bool foundCameraSection = false;

185
    qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex;
186

187
    MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(scanIndex);
188
    if (!settingsItem) {
189
        qWarning() << "Item specified by scanIndex not MissionSettingsItem";
190
        return false;
191 192 193 194
    }

    // Scan through the initial mission items for possible mission settings

195
    scanIndex++;
196 197
    foundCameraSection = settingsItem->_cameraSection.scanForSection(visualItems, scanIndex);
    foundSpeedSection = settingsItem->_speedSection.scanForSection(visualItems, scanIndex);
198

199 200 201 202 203 204 205
    // Look at the end of the mission for end actions

    int lastIndex = visualItems->count() - 1;
    SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(lastIndex);
    if (item) {
        MissionItem& missionItem = item->missionItem();

206 207 208 209 210
        if (item->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH &&
                missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
            qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action RTL";
            settingsItem->_missionEndRTL = true;
            visualItems->removeAt(lastIndex)->deleteLater();
211 212 213
        }
    }

214
    return foundSpeedSection || foundCameraSection;
215 216
}

217
double MissionSettingsItem::complexDistance(void) const
218 219 220 221
{
    return 0;
}

222
void MissionSettingsItem::_setDirty(void)
223 224 225 226
{
    setDirty(true);
}

227
void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
228
{
229 230 231 232
    if (_plannedHomePositionCoordinate != coordinate) {
        _plannedHomePositionCoordinate = coordinate;
        emit coordinateChanged(coordinate);
        emit exitCoordinateChanged(coordinate);
233 234 235 236
        _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
    }
}

237
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
238 239 240 241 242
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
    setDirty(true);
}

243
void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
244 245 246 247 248
{
    if (dirty) {
        setDirty(true);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
249

250
double MissionSettingsItem::specifiedGimbalYaw(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
251 252 253
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
254 255 256 257 258 259 260 261 262 263 264 265

void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
{
    double newAltitude = value.toDouble();

    if (!qFuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {

        _plannedHomePositionCoordinate.setAltitude(newAltitude);
        emit coordinateChanged(_plannedHomePositionCoordinate);
        emit exitCoordinateChanged(_plannedHomePositionCoordinate);
    }
}
266 267 268 269 270 271 272 273 274

double MissionSettingsItem::specifiedFlightSpeed(void)
{
    if (_speedSection.specifyFlightSpeed()) {
        return _speedSection.flightSpeed()->rawValue().toDouble();
    } else {
        return std::numeric_limits<double>::quiet_NaN();
    }
}