MissionSettingsItem.cc 12.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")

DonLakeFlyer's avatar
DonLakeFlyer committed
24
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
25

26
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
27

28 29
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
    : ComplexMissionItem                (vehicle, flyView, parent)
30
    , _plannedHomePositionAltitudeFact  (0, _plannedHomePositionAltitudeName,   FactMetaData::valueTypeDouble)
31 32
    , _cameraSection                    (vehicle)
    , _speedSection                     (vehicle)
33 34 35 36
{
    _editorQml = "qrc:/qml/MissionSettingsEditor.qml";

    if (_metaDataMap.isEmpty()) {
37
        _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), nullptr /* metaDataParent */);
38 39 40 41 42 43
    }

    _plannedHomePositionAltitudeFact.setMetaData    (_metaDataMap[_plannedHomePositionAltitudeName]);
    _plannedHomePositionAltitudeFact.setRawValue    (_plannedHomePositionAltitudeFact.rawDefaultValue());
    setHomePositionSpecialCase(true);

44 45 46
    _cameraSection.setAvailable(true);
    _speedSection.setAvailable(true);

47
    connect(this,               &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
48
    connect(this,               &MissionSettingsItem::missionEndRTLChanged,             this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
49 50
    connect(&_cameraSection,    &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
    connect(&_speedSection,     &CameraSection::itemCountChanged,                       this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
51

52
    connect(this,               &MissionSettingsItem::terrainAltitudeChanged,           this, &MissionSettingsItem::_setHomeAltFromTerrain);
53

54
    connect(&_plannedHomePositionAltitudeFact,  &Fact::rawValueChanged,                 this, &MissionSettingsItem::_updateAltitudeInCoordinate);
55

56 57
    connect(&_cameraSection,    &CameraSection::dirtyChanged,   this, &MissionSettingsItem::_sectionDirtyChanged);
    connect(&_speedSection,     &SpeedSection::dirtyChanged,    this, &MissionSettingsItem::_sectionDirtyChanged);
DonLakeFlyer's avatar
DonLakeFlyer committed
58

59 60 61
    connect(&_cameraSection,    &CameraSection::specifiedGimbalYawChanged,      this, &MissionSettingsItem::specifiedGimbalYawChanged);
    connect(&_cameraSection,    &CameraSection::specifiedGimbalPitchChanged,    this, &MissionSettingsItem::specifiedGimbalPitchChanged);
    connect(&_speedSection,     &SpeedSection::specifiedFlightSpeedChanged,     this, &MissionSettingsItem::specifiedFlightSpeedChanged);
62 63
}

64
int MissionSettingsItem::lastSequenceNumber(void) const
65
{
66
    int lastSequenceNumber = _sequenceNumber;
67

68 69
    lastSequenceNumber += _cameraSection.itemCount();
    lastSequenceNumber += _speedSection.itemCount();
70 71 72 73

    return lastSequenceNumber;
}

74
void MissionSettingsItem::setDirty(bool dirty)
75 76 77
{
    if (_dirty != dirty) {
        _dirty = dirty;
78 79 80 81
        if (!dirty) {
            _cameraSection.setDirty(false);
            _speedSection.setDirty(false);
        }
82 83 84 85
        emit dirtyChanged(_dirty);
    }
}

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

    appendMissionItems(items, this);
91

92
    // First item should be planned home position, we are not responsible 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
    MissionItem* item = nullptr;
161

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

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

191 192 193 194 195 196 197
    // 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
198
        if (missionItem.command() == MAV_CMD_NAV_RETURN_TO_LAUNCH &&
199 200
                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";
201
            _missionEndRTL = true;
202
            visualItems->removeAt(lastIndex)->deleteLater();
203 204 205
        }
    }

206
    return foundSpeedSection || foundCameraSection;
207 208
}

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

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

219
void MissionSettingsItem::_setCoordinateWorker(const QGeoCoordinate& coordinate)
220
{
221 222 223 224 225 226
    if (_plannedHomePositionCoordinate != coordinate) {
        _plannedHomePositionCoordinate = coordinate;
        emit coordinateChanged(coordinate);
        emit exitCoordinateChanged(coordinate);
        _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
    }
227 228
}

229
void MissionSettingsItem::setHomePositionFromVehicle(Vehicle* vehicle)
230
{
231 232 233
    // If the user hasn't moved the planned home position manually we use the value from the vehicle
    if (!_plannedHomePositionMovedByUser) {
        QGeoCoordinate coordinate = vehicle->homePosition();
234
        // ArduPilot tends to send crap home positions at initial vehicle boot, discard them
Don Gagne's avatar
Don Gagne committed
235
        if (coordinate.isValid() && (coordinate.latitude() != 0 || coordinate.longitude() != 0)) {
236 237
            _plannedHomePositionFromVehicle = true;
            _setCoordinateWorker(coordinate);
238
        }
239 240 241
    }
}

242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266
void MissionSettingsItem::setInitialHomePosition(const QGeoCoordinate& coordinate)
{
    _plannedHomePositionMovedByUser = false;
    _plannedHomePositionFromVehicle = false;
    _setCoordinateWorker(coordinate);
}

void MissionSettingsItem::setInitialHomePositionFromUser(const QGeoCoordinate& coordinate)
{
    _plannedHomePositionMovedByUser = true;
    _plannedHomePositionFromVehicle = false;
    _setCoordinateWorker(coordinate);
}


void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
{
    if (coordinate != this->coordinate()) {
        // The user is moving the planned home position manually. Stop tracking vehicle home position.
        _plannedHomePositionMovedByUser = true;
        _plannedHomePositionFromVehicle = false;
        _setCoordinateWorker(coordinate);
    }
}

267
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
268 269 270 271 272
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
    setDirty(true);
}

273
void MissionSettingsItem::_sectionDirtyChanged(bool dirty)
274 275 276 277 278
{
    if (dirty) {
        setDirty(true);
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
279

280
double MissionSettingsItem::specifiedGimbalYaw(void)
DonLakeFlyer's avatar
DonLakeFlyer committed
281 282 283
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalYaw()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}
284

285 286 287 288 289
double MissionSettingsItem::specifiedGimbalPitch(void)
{
    return _cameraSection.specifyGimbal() ? _cameraSection.gimbalPitch()->rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
}

290 291 292 293 294 295 296 297 298 299
void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
{
    double newAltitude = value.toDouble();

    if (!qFuzzyCompare(_plannedHomePositionCoordinate.altitude(), newAltitude)) {
        _plannedHomePositionCoordinate.setAltitude(newAltitude);
        emit coordinateChanged(_plannedHomePositionCoordinate);
        emit exitCoordinateChanged(_plannedHomePositionCoordinate);
    }
}
300 301 302 303 304 305 306 307 308

double MissionSettingsItem::specifiedFlightSpeed(void)
{
    if (_speedSection.specifyFlightSpeed()) {
        return _speedSection.flightSpeed()->rawValue().toDouble();
    } else {
        return std::numeric_limits<double>::quiet_NaN();
    }
}
309 310 311 312 313 314 315 316

void MissionSettingsItem::setMissionEndRTL(bool missionEndRTL)
{
    if (missionEndRTL != _missionEndRTL) {
        _missionEndRTL = missionEndRTL;
        emit missionEndRTLChanged(missionEndRTL);
    }
}
317 318 319

void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
{
320
    if (!_plannedHomePositionFromVehicle && !qIsNaN(terrainAltitude)) {
321 322 323
        _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
    }
}
324 325 326

QString MissionSettingsItem::abbreviation(void) const
{
327
    return _flyView ? tr("H") : tr("Launch");
328
}