MissionSettingsItem.cc 10.3 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
{
    _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);

49 50 51
    _cameraSection.setAvailable(true);
    _speedSection.setAvailable(true);

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

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

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

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

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


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

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

    return lastSequenceNumber;
}

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

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

    appendMissionItems(items, this);
92

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

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

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

    return true;
}

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

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

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

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

    // 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
147 148
                                        coordinate().latitude(),
                                        coordinate().longitude(),
149 150 151
                                        _plannedHomePositionAltitudeFact.rawValue().toDouble(),
                                        true,                   // autoContinue
                                        false,                  // isCurrentItem
152 153
                                        missionItemParent);
    items.append(item);
154

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

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

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

165
    if (_missionEndRTL) {
166 167 168 169 170 171 172 173 174 175 176 177 178 179 180
        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;
    }
}

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

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

    // Scan through the initial mission items for possible mission settings
189 190
    foundCameraSection = _cameraSection.scanForSection(visualItems, scanIndex);
    foundSpeedSection = _speedSection.scanForSection(visualItems, scanIndex);
191

192 193 194 195 196 197 198
    // 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();

Don Gagne's avatar
Don Gagne committed
199
        if (missionItem.command() == MAV_CMD_NAV_RETURN_TO_LAUNCH &&
200 201
                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";
202
            _missionEndRTL = true;
203
            visualItems->removeAt(lastIndex)->deleteLater();
204 205 206
        }
    }

207
    return foundSpeedSection || foundCameraSection;
208 209
}

210
double MissionSettingsItem::complexDistance(void) const
211 212 213 214
{
    return 0;
}

215
void MissionSettingsItem::_setDirty(void)
216 217 218 219
{
    setDirty(true);
}

220
void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
221
{
222
    if (_plannedHomePositionCoordinate != coordinate) {
223 224 225 226 227 228 229 230
        // ArduPilot tends to send crap home positions at initial vehicel boot, discard them
        if (coordinate.latitude() != 0 || coordinate.longitude() != 0) {
            qDebug() << "Setting home position" << coordinate;
            _plannedHomePositionCoordinate = coordinate;
            emit coordinateChanged(coordinate);
            emit exitCoordinateChanged(coordinate);
            _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
        }
231 232 233
    }
}

234
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
235 236 237 238 239
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
    setDirty(true);
}

240
void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
241 242 243 244 245
{
    if (dirty) {
        setDirty(true);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
246

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

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

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

        _plannedHomePositionCoordinate.setAltitude(newAltitude);
        emit coordinateChanged(_plannedHomePositionCoordinate);
        emit exitCoordinateChanged(_plannedHomePositionCoordinate);
    }
}
263 264 265 266 267 268 269 270 271

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